1#![doc = "MAVLink common dialect."]
2#![doc = ""]
3#![doc = "This file was automatically generated, do not edit."]
4#[cfg(feature = "arbitrary")]
5use arbitrary::Arbitrary;
6#[allow(unused_imports)]
7use bitflags::bitflags;
8use mavlink_core::{bytes::Bytes, bytes_mut::BytesMut, MavlinkVersion, Message, MessageData};
9#[allow(unused_imports)]
10use num_derive::FromPrimitive;
11#[allow(unused_imports)]
12use num_derive::ToPrimitive;
13#[allow(unused_imports)]
14use num_traits::FromPrimitive;
15#[allow(unused_imports)]
16use num_traits::ToPrimitive;
17#[cfg(feature = "serde")]
18use serde::{Deserialize, Serialize};
19bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags in the HIGHRES_IMU message indicate which fields have updated since the last message"] pub struct HighresImuUpdatedFlags : u16 { # [doc = "The value in the xacc field has been updated"] const HIGHRES_IMU_UPDATED_XACC = 1 ; # [doc = "The value in the yacc field has been updated"] const HIGHRES_IMU_UPDATED_YACC = 2 ; # [doc = "The value in the zacc field has been updated since"] const HIGHRES_IMU_UPDATED_ZACC = 4 ; # [doc = "The value in the xgyro field has been updated"] const HIGHRES_IMU_UPDATED_XGYRO = 8 ; # [doc = "The value in the ygyro field has been updated"] const HIGHRES_IMU_UPDATED_YGYRO = 16 ; # [doc = "The value in the zgyro field has been updated"] const HIGHRES_IMU_UPDATED_ZGYRO = 32 ; # [doc = "The value in the xmag field has been updated"] const HIGHRES_IMU_UPDATED_XMAG = 64 ; # [doc = "The value in the ymag field has been updated"] const HIGHRES_IMU_UPDATED_YMAG = 128 ; # [doc = "The value in the zmag field has been updated"] const HIGHRES_IMU_UPDATED_ZMAG = 256 ; # [doc = "The value in the abs_pressure field has been updated"] const HIGHRES_IMU_UPDATED_ABS_PRESSURE = 512 ; # [doc = "The value in the diff_pressure field has been updated"] const HIGHRES_IMU_UPDATED_DIFF_PRESSURE = 1024 ; # [doc = "The value in the pressure_alt field has been updated"] const HIGHRES_IMU_UPDATED_PRESSURE_ALT = 2048 ; # [doc = "The value in the temperature field has been updated"] const HIGHRES_IMU_UPDATED_TEMPERATURE = 4096 ; } }
20impl HighresImuUpdatedFlags {
21 pub const DEFAULT: Self = Self::HIGHRES_IMU_UPDATED_XACC;
22}
23impl Default for HighresImuUpdatedFlags {
24 fn default() -> Self {
25 Self::DEFAULT
26 }
27}
28#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
29#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
30#[cfg_attr(feature = "serde", serde(tag = "type"))]
31#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
32#[repr(u32)]
33#[doc = "Enumeration of estimator types"]
34pub enum MavEstimatorType {
35 #[doc = "Unknown type of the estimator."]
36 MAV_ESTIMATOR_TYPE_UNKNOWN = 0,
37 #[doc = "This is a naive estimator without any real covariance feedback."]
38 MAV_ESTIMATOR_TYPE_NAIVE = 1,
39 #[doc = "Computer vision based estimate. Might be up to scale."]
40 MAV_ESTIMATOR_TYPE_VISION = 2,
41 #[doc = "Visual-inertial estimate."]
42 MAV_ESTIMATOR_TYPE_VIO = 3,
43 #[doc = "Plain GPS estimate."]
44 MAV_ESTIMATOR_TYPE_GPS = 4,
45 #[doc = "Estimator integrating GPS and inertial sensing."]
46 MAV_ESTIMATOR_TYPE_GPS_INS = 5,
47 #[doc = "Estimate from external motion capturing system."]
48 MAV_ESTIMATOR_TYPE_MOCAP = 6,
49 #[doc = "Estimator based on lidar sensor input."]
50 MAV_ESTIMATOR_TYPE_LIDAR = 7,
51 #[doc = "Estimator on autopilot."]
52 MAV_ESTIMATOR_TYPE_AUTOPILOT = 8,
53}
54impl MavEstimatorType {
55 pub const DEFAULT: Self = Self::MAV_ESTIMATOR_TYPE_UNKNOWN;
56}
57impl Default for MavEstimatorType {
58 fn default() -> Self {
59 Self::DEFAULT
60 }
61}
62#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
63#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
64#[cfg_attr(feature = "serde", serde(tag = "type"))]
65#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
66#[repr(u32)]
67pub enum MagCalStatus {
68 MAG_CAL_NOT_STARTED = 0,
69 MAG_CAL_WAITING_TO_START = 1,
70 MAG_CAL_RUNNING_STEP_ONE = 2,
71 MAG_CAL_RUNNING_STEP_TWO = 3,
72 MAG_CAL_SUCCESS = 4,
73 MAG_CAL_FAILED = 5,
74 MAG_CAL_BAD_ORIENTATION = 6,
75 MAG_CAL_BAD_RADIUS = 7,
76}
77impl MagCalStatus {
78 pub const DEFAULT: Self = Self::MAG_CAL_NOT_STARTED;
79}
80impl Default for MagCalStatus {
81 fn default() -> Self {
82 Self::DEFAULT
83 }
84}
85#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
86#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
87#[cfg_attr(feature = "serde", serde(tag = "type"))]
88#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
89#[repr(u32)]
90#[doc = "Winch actions."]
91pub enum WinchActions {
92 #[doc = "Allow motor to freewheel."]
93 WINCH_RELAXED = 0,
94 #[doc = "Wind or unwind specified length of line, optionally using specified rate."]
95 WINCH_RELATIVE_LENGTH_CONTROL = 1,
96 #[doc = "Wind or unwind line at specified rate."]
97 WINCH_RATE_CONTROL = 2,
98 #[doc = "Perform the locking sequence to relieve motor while in the fully retracted position. Only action and instance command parameters are used, others are ignored."]
99 WINCH_LOCK = 3,
100 #[doc = "Sequence of drop, slow down, touch down, reel up, lock. Only action and instance command parameters are used, others are ignored."]
101 WINCH_DELIVER = 4,
102 #[doc = "Engage motor and hold current position. Only action and instance command parameters are used, others are ignored."]
103 WINCH_HOLD = 5,
104 #[doc = "Return the reel to the fully retracted position. Only action and instance command parameters are used, others are ignored."]
105 WINCH_RETRACT = 6,
106 #[doc = "Load the reel with line. The winch will calculate the total loaded length and stop when the tension exceeds a threshold. Only action and instance command parameters are used, others are ignored."]
107 WINCH_LOAD_LINE = 7,
108 #[doc = "Spool out the entire length of the line. Only action and instance command parameters are used, others are ignored."]
109 WINCH_ABANDON_LINE = 8,
110 #[doc = "Spools out just enough to present the hook to the user to load the payload. Only action and instance command parameters are used, others are ignored"]
111 WINCH_LOAD_PAYLOAD = 9,
112}
113impl WinchActions {
114 pub const DEFAULT: Self = Self::WINCH_RELAXED;
115}
116impl Default for WinchActions {
117 fn default() -> Self {
118 Self::DEFAULT
119 }
120}
121#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
122#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
123#[cfg_attr(feature = "serde", serde(tag = "type"))]
124#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
125#[repr(u32)]
126#[doc = "Zoom types for MAV_CMD_SET_CAMERA_ZOOM"]
127pub enum CameraZoomType {
128 #[doc = "Zoom one step increment (-1 for wide, 1 for tele)"]
129 ZOOM_TYPE_STEP = 0,
130 #[doc = "Continuous normalized zoom in/out rate until stopped. Range -1..1, negative: wide, positive: narrow/tele, 0 to stop zooming. Other values should be clipped to the range."]
131 ZOOM_TYPE_CONTINUOUS = 1,
132 #[doc = "Zoom value as proportion of full camera range (a percentage value between 0.0 and 100.0)"]
133 ZOOM_TYPE_RANGE = 2,
134 #[doc = "Zoom value/variable focal length in millimetres. Note that there is no message to get the valid zoom range of the camera, so this can type can only be used for cameras where the zoom range is known (implying that this cannot reliably be used in a GCS for an arbitrary camera)"]
135 ZOOM_TYPE_FOCAL_LENGTH = 3,
136 #[doc = "Zoom value as horizontal field of view in degrees."]
137 ZOOM_TYPE_HORIZONTAL_FOV = 4,
138}
139impl CameraZoomType {
140 pub const DEFAULT: Self = Self::ZOOM_TYPE_STEP;
141}
142impl Default for CameraZoomType {
143 fn default() -> Self {
144 Self::DEFAULT
145 }
146}
147#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
148#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
149#[cfg_attr(feature = "serde", serde(tag = "type"))]
150#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
151#[repr(u32)]
152#[doc = "Flags to indicate the type of storage."]
153pub enum StorageType {
154 #[doc = "Storage type is not known."]
155 STORAGE_TYPE_UNKNOWN = 0,
156 #[doc = "Storage type is USB device."]
157 STORAGE_TYPE_USB_STICK = 1,
158 #[doc = "Storage type is SD card."]
159 STORAGE_TYPE_SD = 2,
160 #[doc = "Storage type is microSD card."]
161 STORAGE_TYPE_MICROSD = 3,
162 #[doc = "Storage type is CFast."]
163 STORAGE_TYPE_CF = 4,
164 #[doc = "Storage type is CFexpress."]
165 STORAGE_TYPE_CFE = 5,
166 #[doc = "Storage type is XQD."]
167 STORAGE_TYPE_XQD = 6,
168 #[doc = "Storage type is HD mass storage type."]
169 STORAGE_TYPE_HD = 7,
170 #[doc = "Storage type is other, not listed type."]
171 STORAGE_TYPE_OTHER = 254,
172}
173impl StorageType {
174 pub const DEFAULT: Self = Self::STORAGE_TYPE_UNKNOWN;
175}
176impl Default for StorageType {
177 fn default() -> Self {
178 Self::DEFAULT
179 }
180}
181bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags to report status/failure cases for a power generator (used in GENERATOR_STATUS). Note that FAULTS are conditions that cause the generator to fail. Warnings are conditions that require attention before the next use (they indicate the system is not operating properly)."] pub struct MavGeneratorStatusFlag : u64 { # [doc = "Generator is off."] const MAV_GENERATOR_STATUS_FLAG_OFF = 1 ; # [doc = "Generator is ready to start generating power."] const MAV_GENERATOR_STATUS_FLAG_READY = 2 ; # [doc = "Generator is generating power."] const MAV_GENERATOR_STATUS_FLAG_GENERATING = 4 ; # [doc = "Generator is charging the batteries (generating enough power to charge and provide the load)."] const MAV_GENERATOR_STATUS_FLAG_CHARGING = 8 ; # [doc = "Generator is operating at a reduced maximum power."] const MAV_GENERATOR_STATUS_FLAG_REDUCED_POWER = 16 ; # [doc = "Generator is providing the maximum output."] const MAV_GENERATOR_STATUS_FLAG_MAXPOWER = 32 ; # [doc = "Generator is near the maximum operating temperature, cooling is insufficient."] const MAV_GENERATOR_STATUS_FLAG_OVERTEMP_WARNING = 64 ; # [doc = "Generator hit the maximum operating temperature and shutdown."] const MAV_GENERATOR_STATUS_FLAG_OVERTEMP_FAULT = 128 ; # [doc = "Power electronics are near the maximum operating temperature, cooling is insufficient."] const MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_OVERTEMP_WARNING = 256 ; # [doc = "Power electronics hit the maximum operating temperature and shutdown."] const MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_OVERTEMP_FAULT = 512 ; # [doc = "Power electronics experienced a fault and shutdown."] const MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_FAULT = 1024 ; # [doc = "The power source supplying the generator failed e.g. mechanical generator stopped, tether is no longer providing power, solar cell is in shade, hydrogen reaction no longer happening."] const MAV_GENERATOR_STATUS_FLAG_POWERSOURCE_FAULT = 2048 ; # [doc = "Generator controller having communication problems."] const MAV_GENERATOR_STATUS_FLAG_COMMUNICATION_WARNING = 4096 ; # [doc = "Power electronic or generator cooling system error."] const MAV_GENERATOR_STATUS_FLAG_COOLING_WARNING = 8192 ; # [doc = "Generator controller power rail experienced a fault."] const MAV_GENERATOR_STATUS_FLAG_POWER_RAIL_FAULT = 16384 ; # [doc = "Generator controller exceeded the overcurrent threshold and shutdown to prevent damage."] const MAV_GENERATOR_STATUS_FLAG_OVERCURRENT_FAULT = 32768 ; # [doc = "Generator controller detected a high current going into the batteries and shutdown to prevent battery damage."] const MAV_GENERATOR_STATUS_FLAG_BATTERY_OVERCHARGE_CURRENT_FAULT = 65536 ; # [doc = "Generator controller exceeded it's overvoltage threshold and shutdown to prevent it exceeding the voltage rating."] const MAV_GENERATOR_STATUS_FLAG_OVERVOLTAGE_FAULT = 131072 ; # [doc = "Batteries are under voltage (generator will not start)."] const MAV_GENERATOR_STATUS_FLAG_BATTERY_UNDERVOLT_FAULT = 262144 ; # [doc = "Generator start is inhibited by e.g. a safety switch."] const MAV_GENERATOR_STATUS_FLAG_START_INHIBITED = 524288 ; # [doc = "Generator requires maintenance."] const MAV_GENERATOR_STATUS_FLAG_MAINTENANCE_REQUIRED = 1048576 ; # [doc = "Generator is not ready to generate yet."] const MAV_GENERATOR_STATUS_FLAG_WARMING_UP = 2097152 ; # [doc = "Generator is idle."] const MAV_GENERATOR_STATUS_FLAG_IDLE = 4194304 ; } }
182impl MavGeneratorStatusFlag {
183 pub const DEFAULT: Self = Self::MAV_GENERATOR_STATUS_FLAG_OFF;
184}
185impl Default for MavGeneratorStatusFlag {
186 fn default() -> Self {
187 Self::DEFAULT
188 }
189}
190#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
191#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
192#[cfg_attr(feature = "serde", serde(tag = "type"))]
193#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
194#[repr(u32)]
195#[doc = "Enumeration of battery types"]
196pub enum MavBatteryType {
197 #[doc = "Not specified."]
198 MAV_BATTERY_TYPE_UNKNOWN = 0,
199 #[doc = "Lithium polymer battery"]
200 MAV_BATTERY_TYPE_LIPO = 1,
201 #[doc = "Lithium-iron-phosphate battery"]
202 MAV_BATTERY_TYPE_LIFE = 2,
203 #[doc = "Lithium-ION battery"]
204 MAV_BATTERY_TYPE_LION = 3,
205 #[doc = "Nickel metal hydride battery"]
206 MAV_BATTERY_TYPE_NIMH = 4,
207}
208impl MavBatteryType {
209 pub const DEFAULT: Self = Self::MAV_BATTERY_TYPE_UNKNOWN;
210}
211impl Default for MavBatteryType {
212 fn default() -> Self {
213 Self::DEFAULT
214 }
215}
216bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags used in HIL_ACTUATOR_CONTROLS message."] pub struct HilActuatorControlsFlags : u64 { # [doc = "Simulation is using lockstep"] const HIL_ACTUATOR_CONTROLS_FLAGS_LOCKSTEP = 1 ; } }
217impl HilActuatorControlsFlags {
218 pub const DEFAULT: Self = Self::HIL_ACTUATOR_CONTROLS_FLAGS_LOCKSTEP;
219}
220impl Default for HilActuatorControlsFlags {
221 fn default() -> Self {
222 Self::DEFAULT
223 }
224}
225#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
226#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
227#[cfg_attr(feature = "serde", serde(tag = "type"))]
228#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
229#[repr(u32)]
230#[doc = "Result from a MAVLink command (MAV_CMD)"]
231pub enum MavResult {
232 #[doc = "Command is valid (is supported and has valid parameters), and was executed."]
233 MAV_RESULT_ACCEPTED = 0,
234 #[doc = "Command is valid, but cannot be executed at this time. This is used to indicate a problem that should be fixed just by waiting (e.g. a state machine is busy, can't arm because have not got GPS lock, etc.). Retrying later should work."]
235 MAV_RESULT_TEMPORARILY_REJECTED = 1,
236 #[doc = "Command is invalid (is supported but has invalid parameters). Retrying same command and parameters will not work."]
237 MAV_RESULT_DENIED = 2,
238 #[doc = "Command is not supported (unknown)."]
239 MAV_RESULT_UNSUPPORTED = 3,
240 #[doc = "Command is valid, but execution has failed. This is used to indicate any non-temporary or unexpected problem, i.e. any problem that must be fixed before the command can succeed/be retried. For example, attempting to write a file when out of memory, attempting to arm when sensors are not calibrated, etc."]
241 MAV_RESULT_FAILED = 4,
242 #[doc = "Command is valid and is being executed. This will be followed by further progress updates, i.e. the component may send further COMMAND_ACK messages with result MAV_RESULT_IN_PROGRESS (at a rate decided by the implementation), and must terminate by sending a COMMAND_ACK message with final result of the operation. The COMMAND_ACK.progress field can be used to indicate the progress of the operation."]
243 MAV_RESULT_IN_PROGRESS = 5,
244 #[doc = "Command has been cancelled (as a result of receiving a COMMAND_CANCEL message)."]
245 MAV_RESULT_CANCELLED = 6,
246 #[doc = "Command is only accepted when sent as a COMMAND_LONG."]
247 MAV_RESULT_COMMAND_LONG_ONLY = 7,
248 #[doc = "Command is only accepted when sent as a COMMAND_INT."]
249 MAV_RESULT_COMMAND_INT_ONLY = 8,
250 #[doc = "Command is invalid because a frame is required and the specified frame is not supported."]
251 MAV_RESULT_COMMAND_UNSUPPORTED_MAV_FRAME = 9,
252}
253impl MavResult {
254 pub const DEFAULT: Self = Self::MAV_RESULT_ACCEPTED;
255}
256impl Default for MavResult {
257 fn default() -> Self {
258 Self::DEFAULT
259 }
260}
261bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "These flags indicate status such as data validity of each data source. Set = data valid"] pub struct AdsbFlags : u16 { const ADSB_FLAGS_VALID_COORDS = 1 ; const ADSB_FLAGS_VALID_ALTITUDE = 2 ; const ADSB_FLAGS_VALID_HEADING = 4 ; const ADSB_FLAGS_VALID_VELOCITY = 8 ; const ADSB_FLAGS_VALID_CALLSIGN = 16 ; const ADSB_FLAGS_VALID_SQUAWK = 32 ; const ADSB_FLAGS_SIMULATED = 64 ; const ADSB_FLAGS_VERTICAL_VELOCITY_VALID = 128 ; const ADSB_FLAGS_BARO_VALID = 256 ; const ADSB_FLAGS_SOURCE_UAT = 32768 ; } }
262impl AdsbFlags {
263 pub const DEFAULT: Self = Self::ADSB_FLAGS_VALID_COORDS;
264}
265impl Default for AdsbFlags {
266 fn default() -> Self {
267 Self::DEFAULT
268 }
269}
270#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
271#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
272#[cfg_attr(feature = "serde", serde(tag = "type"))]
273#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
274#[repr(u32)]
275#[doc = "Focus types for MAV_CMD_SET_CAMERA_FOCUS"]
276pub enum SetFocusType {
277 #[doc = "Focus one step increment (-1 for focusing in, 1 for focusing out towards infinity)."]
278 FOCUS_TYPE_STEP = 0,
279 #[doc = "Continuous normalized focus in/out rate until stopped. Range -1..1, negative: in, positive: out towards infinity, 0 to stop focusing. Other values should be clipped to the range."]
280 FOCUS_TYPE_CONTINUOUS = 1,
281 #[doc = "Focus value as proportion of full camera focus range (a value between 0.0 and 100.0)"]
282 FOCUS_TYPE_RANGE = 2,
283 #[doc = "Focus value in metres. Note that there is no message to get the valid focus range of the camera, so this can type can only be used for cameras where the range is known (implying that this cannot reliably be used in a GCS for an arbitrary camera)."]
284 FOCUS_TYPE_METERS = 3,
285 #[doc = "Focus automatically."]
286 FOCUS_TYPE_AUTO = 4,
287 #[doc = "Single auto focus. Mainly used for still pictures. Usually abbreviated as AF-S."]
288 FOCUS_TYPE_AUTO_SINGLE = 5,
289 #[doc = "Continuous auto focus. Mainly used for dynamic scenes. Abbreviated as AF-C."]
290 FOCUS_TYPE_AUTO_CONTINUOUS = 6,
291}
292impl SetFocusType {
293 pub const DEFAULT: Self = Self::FOCUS_TYPE_STEP;
294}
295impl Default for SetFocusType {
296 fn default() -> Self {
297 Self::DEFAULT
298 }
299}
300#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
301#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
302#[cfg_attr(feature = "serde", serde(tag = "type"))]
303#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
304#[repr(u32)]
305pub enum MavOdidOperatorIdType {
306 #[doc = "CAA (Civil Aviation Authority) registered operator ID."]
307 MAV_ODID_OPERATOR_ID_TYPE_CAA = 0,
308}
309impl MavOdidOperatorIdType {
310 pub const DEFAULT: Self = Self::MAV_ODID_OPERATOR_ID_TYPE_CAA;
311}
312impl Default for MavOdidOperatorIdType {
313 fn default() -> Self {
314 Self::DEFAULT
315 }
316}
317#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
318#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
319#[cfg_attr(feature = "serde", serde(tag = "type"))]
320#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
321#[repr(u32)]
322#[doc = "Micro air vehicle / autopilot classes. This identifies the individual model."]
323pub enum MavAutopilot {
324 #[doc = "Generic autopilot, full support for everything"]
325 MAV_AUTOPILOT_GENERIC = 0,
326 #[doc = "Reserved for future use."]
327 MAV_AUTOPILOT_RESERVED = 1,
328 #[doc = "SLUGS autopilot, <http://slugsuav.soe.ucsc.edu>"]
329 MAV_AUTOPILOT_SLUGS = 2,
330 #[doc = "ArduPilot - Plane/Copter/Rover/Sub/Tracker, <https://ardupilot.org>"]
331 MAV_AUTOPILOT_ARDUPILOTMEGA = 3,
332 #[doc = "OpenPilot, <http://openpilot.org>"]
333 MAV_AUTOPILOT_OPENPILOT = 4,
334 #[doc = "Generic autopilot only supporting simple waypoints"]
335 MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY = 5,
336 #[doc = "Generic autopilot supporting waypoints and other simple navigation commands"]
337 MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY = 6,
338 #[doc = "Generic autopilot supporting the full mission command set"]
339 MAV_AUTOPILOT_GENERIC_MISSION_FULL = 7,
340 #[doc = "No valid autopilot, e.g. a GCS or other MAVLink component"]
341 MAV_AUTOPILOT_INVALID = 8,
342 #[doc = "PPZ UAV - <http://nongnu.org/paparazzi>"]
343 MAV_AUTOPILOT_PPZ = 9,
344 #[doc = "UAV Dev Board"]
345 MAV_AUTOPILOT_UDB = 10,
346 #[doc = "FlexiPilot"]
347 MAV_AUTOPILOT_FP = 11,
348 #[doc = "PX4 Autopilot - <http://px4.io/>"]
349 MAV_AUTOPILOT_PX4 = 12,
350 #[doc = "SMACCMPilot - <http://smaccmpilot.org>"]
351 MAV_AUTOPILOT_SMACCMPILOT = 13,
352 #[doc = "AutoQuad -- <http://autoquad.org>"]
353 MAV_AUTOPILOT_AUTOQUAD = 14,
354 #[doc = "Armazila -- <http://armazila.com>"]
355 MAV_AUTOPILOT_ARMAZILA = 15,
356 #[doc = "Aerob -- <http://aerob.ru>"]
357 MAV_AUTOPILOT_AEROB = 16,
358 #[doc = "ASLUAV autopilot -- <http://www.asl.ethz.ch>"]
359 MAV_AUTOPILOT_ASLUAV = 17,
360 #[doc = "SmartAP Autopilot - <http://sky-drones.com>"]
361 MAV_AUTOPILOT_SMARTAP = 18,
362 #[doc = "AirRails - <http://uaventure.com>"]
363 MAV_AUTOPILOT_AIRRAILS = 19,
364 #[doc = "Fusion Reflex - <https://fusion.engineering>"]
365 MAV_AUTOPILOT_REFLEX = 20,
366}
367impl MavAutopilot {
368 pub const DEFAULT: Self = Self::MAV_AUTOPILOT_GENERIC;
369}
370impl Default for MavAutopilot {
371 fn default() -> Self {
372 Self::DEFAULT
373 }
374}
375#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
376#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
377#[cfg_attr(feature = "serde", serde(tag = "type"))]
378#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
379#[repr(u32)]
380#[doc = "Enumeration of distance sensor types"]
381pub enum MavDistanceSensor {
382 #[doc = "Laser rangefinder, e.g. LightWare SF02/F or PulsedLight units"]
383 MAV_DISTANCE_SENSOR_LASER = 0,
384 #[doc = "Ultrasound rangefinder, e.g. MaxBotix units"]
385 MAV_DISTANCE_SENSOR_ULTRASOUND = 1,
386 #[doc = "Infrared rangefinder, e.g. Sharp units"]
387 MAV_DISTANCE_SENSOR_INFRARED = 2,
388 #[doc = "Radar type, e.g. uLanding units"]
389 MAV_DISTANCE_SENSOR_RADAR = 3,
390 #[doc = "Broken or unknown type, e.g. analog units"]
391 MAV_DISTANCE_SENSOR_UNKNOWN = 4,
392}
393impl MavDistanceSensor {
394 pub const DEFAULT: Self = Self::MAV_DISTANCE_SENSOR_LASER;
395}
396impl Default for MavDistanceSensor {
397 fn default() -> Self {
398 Self::DEFAULT
399 }
400}
401#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
402#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
403#[cfg_attr(feature = "serde", serde(tag = "type"))]
404#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
405#[repr(u32)]
406pub enum MavOdidHeightRef {
407 #[doc = "The height field is relative to the take-off location."]
408 MAV_ODID_HEIGHT_REF_OVER_TAKEOFF = 0,
409 #[doc = "The height field is relative to ground."]
410 MAV_ODID_HEIGHT_REF_OVER_GROUND = 1,
411}
412impl MavOdidHeightRef {
413 pub const DEFAULT: Self = Self::MAV_ODID_HEIGHT_REF_OVER_TAKEOFF;
414}
415impl Default for MavOdidHeightRef {
416 fn default() -> Self {
417 Self::DEFAULT
418 }
419}
420#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
421#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
422#[cfg_attr(feature = "serde", serde(tag = "type"))]
423#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
424#[repr(u32)]
425#[doc = "Result from PARAM_EXT_SET message."]
426pub enum ParamAck {
427 #[doc = "Parameter value ACCEPTED and SET"]
428 PARAM_ACK_ACCEPTED = 0,
429 #[doc = "Parameter value UNKNOWN/UNSUPPORTED"]
430 PARAM_ACK_VALUE_UNSUPPORTED = 1,
431 #[doc = "Parameter failed to set"]
432 PARAM_ACK_FAILED = 2,
433 #[doc = "Parameter value received but not yet set/accepted. A subsequent PARAM_EXT_ACK with the final result will follow once operation is completed. This is returned immediately for parameters that take longer to set, indicating that the the parameter was received and does not need to be resent."]
434 PARAM_ACK_IN_PROGRESS = 3,
435}
436impl ParamAck {
437 pub const DEFAULT: Self = Self::PARAM_ACK_ACCEPTED;
438}
439impl Default for ParamAck {
440 fn default() -> Self {
441 Self::DEFAULT
442 }
443}
444#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
445#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
446#[cfg_attr(feature = "serde", serde(tag = "type"))]
447#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
448#[repr(u32)]
449#[doc = "Possible responses from a CELLULAR_CONFIG message."]
450pub enum CellularConfigResponse {
451 #[doc = "Changes accepted."]
452 CELLULAR_CONFIG_RESPONSE_ACCEPTED = 0,
453 #[doc = "Invalid APN."]
454 CELLULAR_CONFIG_RESPONSE_APN_ERROR = 1,
455 #[doc = "Invalid PIN."]
456 CELLULAR_CONFIG_RESPONSE_PIN_ERROR = 2,
457 #[doc = "Changes rejected."]
458 CELLULAR_CONFIG_RESPONSE_REJECTED = 3,
459 #[doc = "PUK is required to unblock SIM card."]
460 CELLULAR_CONFIG_BLOCKED_PUK_REQUIRED = 4,
461}
462impl CellularConfigResponse {
463 pub const DEFAULT: Self = Self::CELLULAR_CONFIG_RESPONSE_ACCEPTED;
464}
465impl Default for CellularConfigResponse {
466 fn default() -> Self {
467 Self::DEFAULT
468 }
469}
470#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
471#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
472#[cfg_attr(feature = "serde", serde(tag = "type"))]
473#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
474#[repr(u32)]
475pub enum MavOdidClassificationType {
476 #[doc = "The classification type for the UA is undeclared."]
477 MAV_ODID_CLASSIFICATION_TYPE_UNDECLARED = 0,
478 #[doc = "The classification type for the UA follows EU (European Union) specifications."]
479 MAV_ODID_CLASSIFICATION_TYPE_EU = 1,
480}
481impl MavOdidClassificationType {
482 pub const DEFAULT: Self = Self::MAV_ODID_CLASSIFICATION_TYPE_UNDECLARED;
483}
484impl Default for MavOdidClassificationType {
485 fn default() -> Self {
486 Self::DEFAULT
487 }
488}
489bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags to indicate usage for a particular storage (see STORAGE_INFORMATION.storage_usage and MAV_CMD_SET_STORAGE_USAGE)."] pub struct StorageUsageFlag : u8 { # [doc = "Always set to 1 (indicates STORAGE_INFORMATION.storage_usage is supported)."] const STORAGE_USAGE_FLAG_SET = 1 ; # [doc = "Storage for saving photos."] const STORAGE_USAGE_FLAG_PHOTO = 2 ; # [doc = "Storage for saving videos."] const STORAGE_USAGE_FLAG_VIDEO = 4 ; # [doc = "Storage for saving logs."] const STORAGE_USAGE_FLAG_LOGS = 8 ; } }
490impl StorageUsageFlag {
491 pub const DEFAULT: Self = Self::STORAGE_USAGE_FLAG_SET;
492}
493impl Default for StorageUsageFlag {
494 fn default() -> Self {
495 Self::DEFAULT
496 }
497}
498#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
499#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
500#[cfg_attr(feature = "serde", serde(tag = "type"))]
501#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
502#[repr(u32)]
503#[doc = "Actions for reading/writing parameters between persistent and volatile storage when using MAV_CMD_PREFLIGHT_STORAGE. (Commonly parameters are loaded from persistent storage (flash/EEPROM) into volatile storage (RAM) on startup and written back when they are changed.)"]
504pub enum PreflightStorageParameterAction {
505 #[doc = "Read all parameters from persistent storage. Replaces values in volatile storage."]
506 PARAM_READ_PERSISTENT = 0,
507 #[doc = "Write all parameter values to persistent storage (flash/EEPROM)"]
508 PARAM_WRITE_PERSISTENT = 1,
509 #[doc = "Reset all user configurable parameters to their default value (including airframe selection, sensor calibration data, safety settings, and so on). Does not reset values that contain operation counters and vehicle computed statistics."]
510 PARAM_RESET_CONFIG_DEFAULT = 2,
511 #[doc = "Reset only sensor calibration parameters to factory defaults (or firmware default if not available)"]
512 PARAM_RESET_SENSOR_DEFAULT = 3,
513 #[doc = "Reset all parameters, including operation counters, to default values"]
514 PARAM_RESET_ALL_DEFAULT = 4,
515}
516impl PreflightStorageParameterAction {
517 pub const DEFAULT: Self = Self::PARAM_READ_PERSISTENT;
518}
519impl Default for PreflightStorageParameterAction {
520 fn default() -> Self {
521 Self::DEFAULT
522 }
523}
524#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
525#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
526#[cfg_attr(feature = "serde", serde(tag = "type"))]
527#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
528#[repr(u32)]
529#[doc = "Precision land modes (used in MAV_CMD_NAV_LAND)."]
530pub enum PrecisionLandMode {
531 #[doc = "Normal (non-precision) landing."]
532 PRECISION_LAND_MODE_DISABLED = 0,
533 #[doc = "Use precision landing if beacon detected when land command accepted, otherwise land normally."]
534 PRECISION_LAND_MODE_OPPORTUNISTIC = 1,
535 #[doc = "Use precision landing, searching for beacon if not found when land command accepted (land normally if beacon cannot be found)."]
536 PRECISION_LAND_MODE_REQUIRED = 2,
537}
538impl PrecisionLandMode {
539 pub const DEFAULT: Self = Self::PRECISION_LAND_MODE_DISABLED;
540}
541impl Default for PrecisionLandMode {
542 fn default() -> Self {
543 Self::DEFAULT
544 }
545}
546#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
547#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
548#[cfg_attr(feature = "serde", serde(tag = "type"))]
549#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
550#[repr(u32)]
551#[doc = "Speed setpoint types used in MAV_CMD_DO_CHANGE_SPEED"]
552pub enum SpeedType {
553 #[doc = "Airspeed"]
554 SPEED_TYPE_AIRSPEED = 0,
555 #[doc = "Groundspeed"]
556 SPEED_TYPE_GROUNDSPEED = 1,
557 #[doc = "Climb speed"]
558 SPEED_TYPE_CLIMB_SPEED = 2,
559 #[doc = "Descent speed"]
560 SPEED_TYPE_DESCENT_SPEED = 3,
561}
562impl SpeedType {
563 pub const DEFAULT: Self = Self::SPEED_TYPE_AIRSPEED;
564}
565impl Default for SpeedType {
566 fn default() -> Self {
567 Self::DEFAULT
568 }
569}
570#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
571#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
572#[cfg_attr(feature = "serde", serde(tag = "type"))]
573#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
574#[repr(u32)]
575#[doc = "Enumeration of landed detector states"]
576pub enum MavLandedState {
577 #[doc = "MAV landed state is unknown"]
578 MAV_LANDED_STATE_UNDEFINED = 0,
579 #[doc = "MAV is landed (on ground)"]
580 MAV_LANDED_STATE_ON_GROUND = 1,
581 #[doc = "MAV is in air"]
582 MAV_LANDED_STATE_IN_AIR = 2,
583 #[doc = "MAV currently taking off"]
584 MAV_LANDED_STATE_TAKEOFF = 3,
585 #[doc = "MAV currently landing"]
586 MAV_LANDED_STATE_LANDING = 4,
587}
588impl MavLandedState {
589 pub const DEFAULT: Self = Self::MAV_LANDED_STATE_UNDEFINED;
590}
591impl Default for MavLandedState {
592 fn default() -> Self {
593 Self::DEFAULT
594 }
595}
596#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
597#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
598#[cfg_attr(feature = "serde", serde(tag = "type"))]
599#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
600#[repr(u32)]
601#[doc = "Video stream encodings"]
602pub enum VideoStreamEncoding {
603 #[doc = "Stream encoding is unknown"]
604 VIDEO_STREAM_ENCODING_UNKNOWN = 0,
605 #[doc = "Stream encoding is H.264"]
606 VIDEO_STREAM_ENCODING_H264 = 1,
607 #[doc = "Stream encoding is H.265"]
608 VIDEO_STREAM_ENCODING_H265 = 2,
609}
610impl VideoStreamEncoding {
611 pub const DEFAULT: Self = Self::VIDEO_STREAM_ENCODING_UNKNOWN;
612}
613impl Default for VideoStreamEncoding {
614 fn default() -> Self {
615 Self::DEFAULT
616 }
617}
618#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
619#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
620#[cfg_attr(feature = "serde", serde(tag = "type"))]
621#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
622#[repr(u32)]
623pub enum MavOdidCategoryEu {
624 #[doc = "The category for the UA, according to the EU specification, is undeclared."]
625 MAV_ODID_CATEGORY_EU_UNDECLARED = 0,
626 #[doc = "The category for the UA, according to the EU specification, is the Open category."]
627 MAV_ODID_CATEGORY_EU_OPEN = 1,
628 #[doc = "The category for the UA, according to the EU specification, is the Specific category."]
629 MAV_ODID_CATEGORY_EU_SPECIFIC = 2,
630 #[doc = "The category for the UA, according to the EU specification, is the Certified category."]
631 MAV_ODID_CATEGORY_EU_CERTIFIED = 3,
632}
633impl MavOdidCategoryEu {
634 pub const DEFAULT: Self = Self::MAV_ODID_CATEGORY_EU_UNDECLARED;
635}
636impl Default for MavOdidCategoryEu {
637 fn default() -> Self {
638 Self::DEFAULT
639 }
640}
641#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
642#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
643#[cfg_attr(feature = "serde", serde(tag = "type"))]
644#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
645#[repr(u32)]
646pub enum MavOdidArmStatus {
647 #[doc = "Passing arming checks."]
648 MAV_ODID_ARM_STATUS_GOOD_TO_ARM = 0,
649 #[doc = "Generic arming failure, see error string for details."]
650 MAV_ODID_ARM_STATUS_PRE_ARM_FAIL_GENERIC = 1,
651}
652impl MavOdidArmStatus {
653 pub const DEFAULT: Self = Self::MAV_ODID_ARM_STATUS_GOOD_TO_ARM;
654}
655impl Default for MavOdidArmStatus {
656 fn default() -> Self {
657 Self::DEFAULT
658 }
659}
660#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
661#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
662#[cfg_attr(feature = "serde", serde(tag = "type"))]
663#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
664#[repr(u32)]
665#[doc = "RC sub-type of types defined in RC_TYPE. Used in MAV_CMD_START_RX_PAIR. Ignored if value does not correspond to the set RC_TYPE."]
666pub enum RcSubType {
667 #[doc = "Spektrum DSM2"]
668 RC_SUB_TYPE_SPEKTRUM_DSM2 = 0,
669 #[doc = "Spektrum DSMX"]
670 RC_SUB_TYPE_SPEKTRUM_DSMX = 1,
671 #[doc = "Spektrum DSMX8"]
672 RC_SUB_TYPE_SPEKTRUM_DSMX8 = 2,
673}
674impl RcSubType {
675 pub const DEFAULT: Self = Self::RC_SUB_TYPE_SPEKTRUM_DSM2;
676}
677impl Default for RcSubType {
678 fn default() -> Self {
679 Self::DEFAULT
680 }
681}
682#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
683#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
684#[cfg_attr(feature = "serde", serde(tag = "type"))]
685#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
686#[repr(u32)]
687#[doc = "Navigational status of AIS vessel, enum duplicated from AIS standard, <https://gpsd.gitlab.io/gpsd/AIVDM.html>"]
688pub enum AisNavStatus {
689 #[doc = "Under way using engine."]
690 UNDER_WAY = 0,
691 AIS_NAV_ANCHORED = 1,
692 AIS_NAV_UN_COMMANDED = 2,
693 AIS_NAV_RESTRICTED_MANOEUVERABILITY = 3,
694 AIS_NAV_DRAUGHT_CONSTRAINED = 4,
695 AIS_NAV_MOORED = 5,
696 AIS_NAV_AGROUND = 6,
697 AIS_NAV_FISHING = 7,
698 AIS_NAV_SAILING = 8,
699 AIS_NAV_RESERVED_HSC = 9,
700 AIS_NAV_RESERVED_WIG = 10,
701 AIS_NAV_RESERVED_1 = 11,
702 AIS_NAV_RESERVED_2 = 12,
703 AIS_NAV_RESERVED_3 = 13,
704 #[doc = "Search And Rescue Transponder."]
705 AIS_NAV_AIS_SART = 14,
706 #[doc = "Not available (default)."]
707 AIS_NAV_UNKNOWN = 15,
708}
709impl AisNavStatus {
710 pub const DEFAULT: Self = Self::UNDER_WAY;
711}
712impl Default for AisNavStatus {
713 fn default() -> Self {
714 Self::DEFAULT
715 }
716}
717#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
718#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
719#[cfg_attr(feature = "serde", serde(tag = "type"))]
720#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
721#[repr(u32)]
722pub enum MavOdidAuthType {
723 #[doc = "No authentication type is specified."]
724 MAV_ODID_AUTH_TYPE_NONE = 0,
725 #[doc = "Signature for the UAS (Unmanned Aircraft System) ID."]
726 MAV_ODID_AUTH_TYPE_UAS_ID_SIGNATURE = 1,
727 #[doc = "Signature for the Operator ID."]
728 MAV_ODID_AUTH_TYPE_OPERATOR_ID_SIGNATURE = 2,
729 #[doc = "Signature for the entire message set."]
730 MAV_ODID_AUTH_TYPE_MESSAGE_SET_SIGNATURE = 3,
731 #[doc = "Authentication is provided by Network Remote ID."]
732 MAV_ODID_AUTH_TYPE_NETWORK_REMOTE_ID = 4,
733 #[doc = "The exact authentication type is indicated by the first byte of authentication_data and these type values are managed by ICAO."]
734 MAV_ODID_AUTH_TYPE_SPECIFIC_AUTHENTICATION = 5,
735}
736impl MavOdidAuthType {
737 pub const DEFAULT: Self = Self::MAV_ODID_AUTH_TYPE_NONE;
738}
739impl Default for MavOdidAuthType {
740 fn default() -> Self {
741 Self::DEFAULT
742 }
743}
744#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
745#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
746#[cfg_attr(feature = "serde", serde(tag = "type"))]
747#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
748#[repr(u32)]
749#[doc = "Specifies the conditions under which the MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN command should be accepted."]
750pub enum RebootShutdownConditions {
751 #[doc = "Reboot/Shutdown only if allowed by safety checks, such as being landed."]
752 REBOOT_SHUTDOWN_CONDITIONS_SAFETY_INTERLOCKED = 0,
753 #[doc = "Force reboot/shutdown of the autopilot/component regardless of system state."]
754 REBOOT_SHUTDOWN_CONDITIONS_FORCE = 20190226,
755}
756impl RebootShutdownConditions {
757 pub const DEFAULT: Self = Self::REBOOT_SHUTDOWN_CONDITIONS_SAFETY_INTERLOCKED;
758}
759impl Default for RebootShutdownConditions {
760 fn default() -> Self {
761 Self::DEFAULT
762 }
763}
764#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
765#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
766#[cfg_attr(feature = "serde", serde(tag = "type"))]
767#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
768#[repr(u32)]
769#[doc = "These values encode the bit positions of the decode position. These values can be used to read the value of a flag bit by combining the base_mode variable with AND with the flag position value. The result will be either 0 or 1, depending on if the flag is set or not."]
770pub enum MavModeFlagDecodePosition {
771 #[doc = "First bit: 10000000"]
772 MAV_MODE_FLAG_DECODE_POSITION_SAFETY = 128,
773 #[doc = "Second bit: 01000000"]
774 MAV_MODE_FLAG_DECODE_POSITION_MANUAL = 64,
775 #[doc = "Third bit: 00100000"]
776 MAV_MODE_FLAG_DECODE_POSITION_HIL = 32,
777 #[doc = "Fourth bit: 00010000"]
778 MAV_MODE_FLAG_DECODE_POSITION_STABILIZE = 16,
779 #[doc = "Fifth bit: 00001000"]
780 MAV_MODE_FLAG_DECODE_POSITION_GUIDED = 8,
781 #[doc = "Sixth bit: 00000100"]
782 MAV_MODE_FLAG_DECODE_POSITION_AUTO = 4,
783 #[doc = "Seventh bit: 00000010"]
784 MAV_MODE_FLAG_DECODE_POSITION_TEST = 2,
785 #[doc = "Eighth bit: 00000001"]
786 MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE = 1,
787}
788impl MavModeFlagDecodePosition {
789 pub const DEFAULT: Self = Self::MAV_MODE_FLAG_DECODE_POSITION_SAFETY;
790}
791impl Default for MavModeFlagDecodePosition {
792 fn default() -> Self {
793 Self::DEFAULT
794 }
795}
796#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
797#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
798#[cfg_attr(feature = "serde", serde(tag = "type"))]
799#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
800#[repr(u32)]
801#[doc = "Type of GPS fix"]
802pub enum GpsFixType {
803 #[doc = "No GPS connected"]
804 GPS_FIX_TYPE_NO_GPS = 0,
805 #[doc = "No position information, GPS is connected"]
806 GPS_FIX_TYPE_NO_FIX = 1,
807 #[doc = "2D position"]
808 GPS_FIX_TYPE_2D_FIX = 2,
809 #[doc = "3D position"]
810 GPS_FIX_TYPE_3D_FIX = 3,
811 #[doc = "DGPS/SBAS aided 3D position"]
812 GPS_FIX_TYPE_DGPS = 4,
813 #[doc = "RTK float, 3D position"]
814 GPS_FIX_TYPE_RTK_FLOAT = 5,
815 #[doc = "RTK Fixed, 3D position"]
816 GPS_FIX_TYPE_RTK_FIXED = 6,
817 #[doc = "Static fixed, typically used for base stations"]
818 GPS_FIX_TYPE_STATIC = 7,
819 #[doc = "PPP, 3D position."]
820 GPS_FIX_TYPE_PPP = 8,
821}
822impl GpsFixType {
823 pub const DEFAULT: Self = Self::GPS_FIX_TYPE_NO_GPS;
824}
825impl Default for GpsFixType {
826 fn default() -> Self {
827 Self::DEFAULT
828 }
829}
830bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Stream status flags (Bitmap)"] pub struct VideoStreamStatusFlags : u16 { # [doc = "Stream is active (running)"] const VIDEO_STREAM_STATUS_FLAGS_RUNNING = 1 ; # [doc = "Stream is thermal imaging"] const VIDEO_STREAM_STATUS_FLAGS_THERMAL = 2 ; # [doc = "Stream can report absolute thermal range (see CAMERA_THERMAL_RANGE)."] const VIDEO_STREAM_STATUS_FLAGS_THERMAL_RANGE_ENABLED = 4 ; } }
831impl VideoStreamStatusFlags {
832 pub const DEFAULT: Self = Self::VIDEO_STREAM_STATUS_FLAGS_RUNNING;
833}
834impl Default for VideoStreamStatusFlags {
835 fn default() -> Self {
836 Self::DEFAULT
837 }
838}
839#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
840#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
841#[cfg_attr(feature = "serde", serde(tag = "type"))]
842#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
843#[repr(u32)]
844#[doc = "Airborne status of UAS."]
845pub enum UtmFlightState {
846 #[doc = "The flight state can't be determined."]
847 UTM_FLIGHT_STATE_UNKNOWN = 1,
848 #[doc = "UAS on ground."]
849 UTM_FLIGHT_STATE_GROUND = 2,
850 #[doc = "UAS airborne."]
851 UTM_FLIGHT_STATE_AIRBORNE = 3,
852 #[doc = "UAS is in an emergency flight state."]
853 UTM_FLIGHT_STATE_EMERGENCY = 16,
854 #[doc = "UAS has no active controls."]
855 UTM_FLIGHT_STATE_NOCTRL = 32,
856}
857impl UtmFlightState {
858 pub const DEFAULT: Self = Self::UTM_FLIGHT_STATE_UNKNOWN;
859}
860impl Default for UtmFlightState {
861 fn default() -> Self {
862 Self::DEFAULT
863 }
864}
865bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Gimbal manager high level capability flags (bitmap). The first 16 bits are identical to the GIMBAL_DEVICE_CAP_FLAGS. However, the gimbal manager does not need to copy the flags from the gimbal but can also enhance the capabilities and thus add flags."] pub struct GimbalManagerCapFlags : u32 { # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_RETRACT = 1 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_NEUTRAL = 2 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_AXIS = 4 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_FOLLOW = 8 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_LOCK = 16 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_AXIS = 32 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_FOLLOW = 64 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_LOCK = 128 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_AXIS = 256 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_FOLLOW = 512 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_LOCK = 1024 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAW."] const GIMBAL_MANAGER_CAP_FLAGS_SUPPORTS_INFINITE_YAW = 2048 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_YAW_IN_EARTH_FRAME."] const GIMBAL_MANAGER_CAP_FLAGS_SUPPORTS_YAW_IN_EARTH_FRAME = 4096 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_RC_INPUTS."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_RC_INPUTS = 8192 ; # [doc = "Gimbal manager supports to point to a local position."] const GIMBAL_MANAGER_CAP_FLAGS_CAN_POINT_LOCATION_LOCAL = 65536 ; # [doc = "Gimbal manager supports to point to a global latitude, longitude, altitude position."] const GIMBAL_MANAGER_CAP_FLAGS_CAN_POINT_LOCATION_GLOBAL = 131072 ; } }
866impl GimbalManagerCapFlags {
867 pub const DEFAULT: Self = Self::GIMBAL_MANAGER_CAP_FLAGS_HAS_RETRACT;
868}
869impl Default for GimbalManagerCapFlags {
870 fn default() -> Self {
871 Self::DEFAULT
872 }
873}
874#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
875#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
876#[cfg_attr(feature = "serde", serde(tag = "type"))]
877#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
878#[repr(u32)]
879#[doc = "Enumeration of VTOL states"]
880pub enum MavVtolState {
881 #[doc = "MAV is not configured as VTOL"]
882 MAV_VTOL_STATE_UNDEFINED = 0,
883 #[doc = "VTOL is in transition from multicopter to fixed-wing"]
884 MAV_VTOL_STATE_TRANSITION_TO_FW = 1,
885 #[doc = "VTOL is in transition from fixed-wing to multicopter"]
886 MAV_VTOL_STATE_TRANSITION_TO_MC = 2,
887 #[doc = "VTOL is in multicopter state"]
888 MAV_VTOL_STATE_MC = 3,
889 #[doc = "VTOL is in fixed-wing state"]
890 MAV_VTOL_STATE_FW = 4,
891}
892impl MavVtolState {
893 pub const DEFAULT: Self = Self::MAV_VTOL_STATE_UNDEFINED;
894}
895impl Default for MavVtolState {
896 fn default() -> Self {
897 Self::DEFAULT
898 }
899}
900#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
901#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
902#[cfg_attr(feature = "serde", serde(tag = "type"))]
903#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
904#[repr(u32)]
905#[doc = "List of possible units where failures can be injected."]
906pub enum FailureUnit {
907 FAILURE_UNIT_SENSOR_GYRO = 0,
908 FAILURE_UNIT_SENSOR_ACCEL = 1,
909 FAILURE_UNIT_SENSOR_MAG = 2,
910 FAILURE_UNIT_SENSOR_BARO = 3,
911 FAILURE_UNIT_SENSOR_GPS = 4,
912 FAILURE_UNIT_SENSOR_OPTICAL_FLOW = 5,
913 FAILURE_UNIT_SENSOR_VIO = 6,
914 FAILURE_UNIT_SENSOR_DISTANCE_SENSOR = 7,
915 FAILURE_UNIT_SENSOR_AIRSPEED = 8,
916 FAILURE_UNIT_SYSTEM_BATTERY = 100,
917 FAILURE_UNIT_SYSTEM_MOTOR = 101,
918 FAILURE_UNIT_SYSTEM_SERVO = 102,
919 FAILURE_UNIT_SYSTEM_AVOIDANCE = 103,
920 FAILURE_UNIT_SYSTEM_RC_SIGNAL = 104,
921 FAILURE_UNIT_SYSTEM_MAVLINK_SIGNAL = 105,
922}
923impl FailureUnit {
924 pub const DEFAULT: Self = Self::FAILURE_UNIT_SENSOR_GYRO;
925}
926impl Default for FailureUnit {
927 fn default() -> Self {
928 Self::DEFAULT
929 }
930}
931#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
932#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
933#[cfg_attr(feature = "serde", serde(tag = "type"))]
934#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
935#[repr(u32)]
936#[doc = "WiFi Mode."]
937pub enum WifiConfigApMode {
938 #[doc = "WiFi mode is undefined."]
939 WIFI_CONFIG_AP_MODE_UNDEFINED = 0,
940 #[doc = "WiFi configured as an access point."]
941 WIFI_CONFIG_AP_MODE_AP = 1,
942 #[doc = "WiFi configured as a station connected to an existing local WiFi network."]
943 WIFI_CONFIG_AP_MODE_STATION = 2,
944 #[doc = "WiFi disabled."]
945 WIFI_CONFIG_AP_MODE_DISABLED = 3,
946}
947impl WifiConfigApMode {
948 pub const DEFAULT: Self = Self::WIFI_CONFIG_AP_MODE_UNDEFINED;
949}
950impl Default for WifiConfigApMode {
951 fn default() -> Self {
952 Self::DEFAULT
953 }
954}
955#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
956#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
957#[cfg_attr(feature = "serde", serde(tag = "type"))]
958#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
959#[repr(u32)]
960#[doc = "Enumeration of sensor orientation, according to its rotations"]
961pub enum MavSensorOrientation {
962 #[doc = "Roll: 0, Pitch: 0, Yaw: 0"]
963 MAV_SENSOR_ROTATION_NONE = 0,
964 #[doc = "Roll: 0, Pitch: 0, Yaw: 45"]
965 MAV_SENSOR_ROTATION_YAW_45 = 1,
966 #[doc = "Roll: 0, Pitch: 0, Yaw: 90"]
967 MAV_SENSOR_ROTATION_YAW_90 = 2,
968 #[doc = "Roll: 0, Pitch: 0, Yaw: 135"]
969 MAV_SENSOR_ROTATION_YAW_135 = 3,
970 #[doc = "Roll: 0, Pitch: 0, Yaw: 180"]
971 MAV_SENSOR_ROTATION_YAW_180 = 4,
972 #[doc = "Roll: 0, Pitch: 0, Yaw: 225"]
973 MAV_SENSOR_ROTATION_YAW_225 = 5,
974 #[doc = "Roll: 0, Pitch: 0, Yaw: 270"]
975 MAV_SENSOR_ROTATION_YAW_270 = 6,
976 #[doc = "Roll: 0, Pitch: 0, Yaw: 315"]
977 MAV_SENSOR_ROTATION_YAW_315 = 7,
978 #[doc = "Roll: 180, Pitch: 0, Yaw: 0"]
979 MAV_SENSOR_ROTATION_ROLL_180 = 8,
980 #[doc = "Roll: 180, Pitch: 0, Yaw: 45"]
981 MAV_SENSOR_ROTATION_ROLL_180_YAW_45 = 9,
982 #[doc = "Roll: 180, Pitch: 0, Yaw: 90"]
983 MAV_SENSOR_ROTATION_ROLL_180_YAW_90 = 10,
984 #[doc = "Roll: 180, Pitch: 0, Yaw: 135"]
985 MAV_SENSOR_ROTATION_ROLL_180_YAW_135 = 11,
986 #[doc = "Roll: 0, Pitch: 180, Yaw: 0"]
987 MAV_SENSOR_ROTATION_PITCH_180 = 12,
988 #[doc = "Roll: 180, Pitch: 0, Yaw: 225"]
989 MAV_SENSOR_ROTATION_ROLL_180_YAW_225 = 13,
990 #[doc = "Roll: 180, Pitch: 0, Yaw: 270"]
991 MAV_SENSOR_ROTATION_ROLL_180_YAW_270 = 14,
992 #[doc = "Roll: 180, Pitch: 0, Yaw: 315"]
993 MAV_SENSOR_ROTATION_ROLL_180_YAW_315 = 15,
994 #[doc = "Roll: 90, Pitch: 0, Yaw: 0"]
995 MAV_SENSOR_ROTATION_ROLL_90 = 16,
996 #[doc = "Roll: 90, Pitch: 0, Yaw: 45"]
997 MAV_SENSOR_ROTATION_ROLL_90_YAW_45 = 17,
998 #[doc = "Roll: 90, Pitch: 0, Yaw: 90"]
999 MAV_SENSOR_ROTATION_ROLL_90_YAW_90 = 18,
1000 #[doc = "Roll: 90, Pitch: 0, Yaw: 135"]
1001 MAV_SENSOR_ROTATION_ROLL_90_YAW_135 = 19,
1002 #[doc = "Roll: 270, Pitch: 0, Yaw: 0"]
1003 MAV_SENSOR_ROTATION_ROLL_270 = 20,
1004 #[doc = "Roll: 270, Pitch: 0, Yaw: 45"]
1005 MAV_SENSOR_ROTATION_ROLL_270_YAW_45 = 21,
1006 #[doc = "Roll: 270, Pitch: 0, Yaw: 90"]
1007 MAV_SENSOR_ROTATION_ROLL_270_YAW_90 = 22,
1008 #[doc = "Roll: 270, Pitch: 0, Yaw: 135"]
1009 MAV_SENSOR_ROTATION_ROLL_270_YAW_135 = 23,
1010 #[doc = "Roll: 0, Pitch: 90, Yaw: 0"]
1011 MAV_SENSOR_ROTATION_PITCH_90 = 24,
1012 #[doc = "Roll: 0, Pitch: 270, Yaw: 0"]
1013 MAV_SENSOR_ROTATION_PITCH_270 = 25,
1014 #[doc = "Roll: 0, Pitch: 180, Yaw: 90"]
1015 MAV_SENSOR_ROTATION_PITCH_180_YAW_90 = 26,
1016 #[doc = "Roll: 0, Pitch: 180, Yaw: 270"]
1017 MAV_SENSOR_ROTATION_PITCH_180_YAW_270 = 27,
1018 #[doc = "Roll: 90, Pitch: 90, Yaw: 0"]
1019 MAV_SENSOR_ROTATION_ROLL_90_PITCH_90 = 28,
1020 #[doc = "Roll: 180, Pitch: 90, Yaw: 0"]
1021 MAV_SENSOR_ROTATION_ROLL_180_PITCH_90 = 29,
1022 #[doc = "Roll: 270, Pitch: 90, Yaw: 0"]
1023 MAV_SENSOR_ROTATION_ROLL_270_PITCH_90 = 30,
1024 #[doc = "Roll: 90, Pitch: 180, Yaw: 0"]
1025 MAV_SENSOR_ROTATION_ROLL_90_PITCH_180 = 31,
1026 #[doc = "Roll: 270, Pitch: 180, Yaw: 0"]
1027 MAV_SENSOR_ROTATION_ROLL_270_PITCH_180 = 32,
1028 #[doc = "Roll: 90, Pitch: 270, Yaw: 0"]
1029 MAV_SENSOR_ROTATION_ROLL_90_PITCH_270 = 33,
1030 #[doc = "Roll: 180, Pitch: 270, Yaw: 0"]
1031 MAV_SENSOR_ROTATION_ROLL_180_PITCH_270 = 34,
1032 #[doc = "Roll: 270, Pitch: 270, Yaw: 0"]
1033 MAV_SENSOR_ROTATION_ROLL_270_PITCH_270 = 35,
1034 #[doc = "Roll: 90, Pitch: 180, Yaw: 90"]
1035 MAV_SENSOR_ROTATION_ROLL_90_PITCH_180_YAW_90 = 36,
1036 #[doc = "Roll: 90, Pitch: 0, Yaw: 270"]
1037 MAV_SENSOR_ROTATION_ROLL_90_YAW_270 = 37,
1038 #[doc = "Roll: 90, Pitch: 68, Yaw: 293"]
1039 MAV_SENSOR_ROTATION_ROLL_90_PITCH_68_YAW_293 = 38,
1040 #[doc = "Pitch: 315"]
1041 MAV_SENSOR_ROTATION_PITCH_315 = 39,
1042 #[doc = "Roll: 90, Pitch: 315"]
1043 MAV_SENSOR_ROTATION_ROLL_90_PITCH_315 = 40,
1044 #[doc = "Custom orientation"]
1045 MAV_SENSOR_ROTATION_CUSTOM = 100,
1046}
1047impl MavSensorOrientation {
1048 pub const DEFAULT: Self = Self::MAV_SENSOR_ROTATION_NONE;
1049}
1050impl Default for MavSensorOrientation {
1051 fn default() -> Self {
1052 Self::DEFAULT
1053 }
1054}
1055bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags to report ESC failures."] pub struct EscFailureFlags : u16 { # [doc = "Over current failure."] const ESC_FAILURE_OVER_CURRENT = 1 ; # [doc = "Over voltage failure."] const ESC_FAILURE_OVER_VOLTAGE = 2 ; # [doc = "Over temperature failure."] const ESC_FAILURE_OVER_TEMPERATURE = 4 ; # [doc = "Over RPM failure."] const ESC_FAILURE_OVER_RPM = 8 ; # [doc = "Inconsistent command failure i.e. out of bounds."] const ESC_FAILURE_INCONSISTENT_CMD = 16 ; # [doc = "Motor stuck failure."] const ESC_FAILURE_MOTOR_STUCK = 32 ; # [doc = "Generic ESC failure."] const ESC_FAILURE_GENERIC = 64 ; } }
1056impl EscFailureFlags {
1057 pub const DEFAULT: Self = Self::ESC_FAILURE_OVER_CURRENT;
1058}
1059impl Default for EscFailureFlags {
1060 fn default() -> Self {
1061 Self::DEFAULT
1062 }
1063}
1064bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Mode properties."] pub struct MavModeProperty : u32 { # [doc = "If set, this mode is an advanced mode. For example a rate-controlled manual mode might be advanced, whereas a position-controlled manual mode is not. A GCS can optionally use this flag to configure the UI for its intended users."] const MAV_MODE_PROPERTY_ADVANCED = 1 ; # [doc = "If set, this mode should not be added to the list of selectable modes. The mode might still be selected by the FC directly (for example as part of a failsafe)."] const MAV_MODE_PROPERTY_NOT_USER_SELECTABLE = 2 ; # [doc = "If set, this mode is automatically controlled (it may use but does not require a manual controller). If unset the mode is a assumed to require user input (be a manual mode)."] const MAV_MODE_PROPERTY_AUTO_MODE = 4 ; } }
1065impl MavModeProperty {
1066 pub const DEFAULT: Self = Self::MAV_MODE_PROPERTY_ADVANCED;
1067}
1068impl Default for MavModeProperty {
1069 fn default() -> Self {
1070 Self::DEFAULT
1071 }
1072}
1073#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1074#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1075#[cfg_attr(feature = "serde", serde(tag = "type"))]
1076#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1077#[repr(u32)]
1078#[doc = "Yaw behaviour during orbit flight."]
1079pub enum OrbitYawBehaviour {
1080 #[doc = "Vehicle front points to the center (default)."]
1081 ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TO_CIRCLE_CENTER = 0,
1082 #[doc = "Vehicle front holds heading when message received."]
1083 ORBIT_YAW_BEHAVIOUR_HOLD_INITIAL_HEADING = 1,
1084 #[doc = "Yaw uncontrolled."]
1085 ORBIT_YAW_BEHAVIOUR_UNCONTROLLED = 2,
1086 #[doc = "Vehicle front follows flight path (tangential to circle)."]
1087 ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TANGENT_TO_CIRCLE = 3,
1088 #[doc = "Yaw controlled by RC input."]
1089 ORBIT_YAW_BEHAVIOUR_RC_CONTROLLED = 4,
1090 #[doc = "Vehicle uses current yaw behaviour (unchanged). The vehicle-default yaw behaviour is used if this value is specified when orbit is first commanded."]
1091 ORBIT_YAW_BEHAVIOUR_UNCHANGED = 5,
1092}
1093impl OrbitYawBehaviour {
1094 pub const DEFAULT: Self = Self::ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TO_CIRCLE_CENTER;
1095}
1096impl Default for OrbitYawBehaviour {
1097 fn default() -> Self {
1098 Self::DEFAULT
1099 }
1100}
1101#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1102#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1103#[cfg_attr(feature = "serde", serde(tag = "type"))]
1104#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1105#[repr(u32)]
1106#[doc = "RTK GPS baseline coordinate system, used for RTK corrections"]
1107pub enum RtkBaselineCoordinateSystem {
1108 #[doc = "Earth-centered, Earth-fixed"]
1109 RTK_BASELINE_COORDINATE_SYSTEM_ECEF = 0,
1110 #[doc = "RTK basestation centered, north, east, down"]
1111 RTK_BASELINE_COORDINATE_SYSTEM_NED = 1,
1112}
1113impl RtkBaselineCoordinateSystem {
1114 pub const DEFAULT: Self = Self::RTK_BASELINE_COORDINATE_SYSTEM_ECEF;
1115}
1116impl Default for RtkBaselineCoordinateSystem {
1117 fn default() -> Self {
1118 Self::DEFAULT
1119 }
1120}
1121#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1122#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1123#[cfg_attr(feature = "serde", serde(tag = "type"))]
1124#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1125#[repr(u32)]
1126#[doc = "ADSB classification for the type of vehicle emitting the transponder signal"]
1127pub enum AdsbEmitterType {
1128 ADSB_EMITTER_TYPE_NO_INFO = 0,
1129 ADSB_EMITTER_TYPE_LIGHT = 1,
1130 ADSB_EMITTER_TYPE_SMALL = 2,
1131 ADSB_EMITTER_TYPE_LARGE = 3,
1132 ADSB_EMITTER_TYPE_HIGH_VORTEX_LARGE = 4,
1133 ADSB_EMITTER_TYPE_HEAVY = 5,
1134 ADSB_EMITTER_TYPE_HIGHLY_MANUV = 6,
1135 ADSB_EMITTER_TYPE_ROTOCRAFT = 7,
1136 ADSB_EMITTER_TYPE_UNASSIGNED = 8,
1137 ADSB_EMITTER_TYPE_GLIDER = 9,
1138 ADSB_EMITTER_TYPE_LIGHTER_AIR = 10,
1139 ADSB_EMITTER_TYPE_PARACHUTE = 11,
1140 ADSB_EMITTER_TYPE_ULTRA_LIGHT = 12,
1141 ADSB_EMITTER_TYPE_UNASSIGNED2 = 13,
1142 ADSB_EMITTER_TYPE_UAV = 14,
1143 ADSB_EMITTER_TYPE_SPACE = 15,
1144 ADSB_EMITTER_TYPE_UNASSGINED3 = 16,
1145 ADSB_EMITTER_TYPE_EMERGENCY_SURFACE = 17,
1146 ADSB_EMITTER_TYPE_SERVICE_SURFACE = 18,
1147 ADSB_EMITTER_TYPE_POINT_OBSTACLE = 19,
1148}
1149impl AdsbEmitterType {
1150 pub const DEFAULT: Self = Self::ADSB_EMITTER_TYPE_NO_INFO;
1151}
1152impl Default for AdsbEmitterType {
1153 fn default() -> Self {
1154 Self::DEFAULT
1155 }
1156}
1157#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1158#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1159#[cfg_attr(feature = "serde", serde(tag = "type"))]
1160#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1161#[repr(u32)]
1162#[doc = "Enumeration of the ADSB altimeter types"]
1163pub enum AdsbAltitudeType {
1164 #[doc = "Altitude reported from a Baro source using QNH reference"]
1165 ADSB_ALTITUDE_TYPE_PRESSURE_QNH = 0,
1166 #[doc = "Altitude reported from a GNSS source"]
1167 ADSB_ALTITUDE_TYPE_GEOMETRIC = 1,
1168}
1169impl AdsbAltitudeType {
1170 pub const DEFAULT: Self = Self::ADSB_ALTITUDE_TYPE_PRESSURE_QNH;
1171}
1172impl Default for AdsbAltitudeType {
1173 fn default() -> Self {
1174 Self::DEFAULT
1175 }
1176}
1177#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1178#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1179#[cfg_attr(feature = "serde", serde(tag = "type"))]
1180#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1181#[repr(u32)]
1182#[doc = "Camera Modes."]
1183pub enum CameraMode {
1184 #[doc = "Camera is in image/photo capture mode."]
1185 CAMERA_MODE_IMAGE = 0,
1186 #[doc = "Camera is in video capture mode."]
1187 CAMERA_MODE_VIDEO = 1,
1188 #[doc = "Camera is in image survey capture mode. It allows for camera controller to do specific settings for surveys."]
1189 CAMERA_MODE_IMAGE_SURVEY = 2,
1190}
1191impl CameraMode {
1192 pub const DEFAULT: Self = Self::CAMERA_MODE_IMAGE;
1193}
1194impl Default for CameraMode {
1195 fn default() -> Self {
1196 Self::DEFAULT
1197 }
1198}
1199bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "These flags are used in the AIS_VESSEL.fields bitmask to indicate validity of data in the other message fields. When set, the data is valid."] pub struct AisFlags : u16 { # [doc = "1 = Position accuracy less than 10m, 0 = position accuracy greater than 10m."] const AIS_FLAGS_POSITION_ACCURACY = 1 ; const AIS_FLAGS_VALID_COG = 2 ; const AIS_FLAGS_VALID_VELOCITY = 4 ; # [doc = "1 = Velocity over 52.5765m/s (102.2 knots)"] const AIS_FLAGS_HIGH_VELOCITY = 8 ; const AIS_FLAGS_VALID_TURN_RATE = 16 ; # [doc = "Only the sign of the returned turn rate value is valid, either greater than 5deg/30s or less than -5deg/30s"] const AIS_FLAGS_TURN_RATE_SIGN_ONLY = 32 ; const AIS_FLAGS_VALID_DIMENSIONS = 64 ; # [doc = "Distance to bow is larger than 511m"] const AIS_FLAGS_LARGE_BOW_DIMENSION = 128 ; # [doc = "Distance to stern is larger than 511m"] const AIS_FLAGS_LARGE_STERN_DIMENSION = 256 ; # [doc = "Distance to port side is larger than 63m"] const AIS_FLAGS_LARGE_PORT_DIMENSION = 512 ; # [doc = "Distance to starboard side is larger than 63m"] const AIS_FLAGS_LARGE_STARBOARD_DIMENSION = 1024 ; const AIS_FLAGS_VALID_CALLSIGN = 2048 ; const AIS_FLAGS_VALID_NAME = 4096 ; } }
1200impl AisFlags {
1201 pub const DEFAULT: Self = Self::AIS_FLAGS_POSITION_ACCURACY;
1202}
1203impl Default for AisFlags {
1204 fn default() -> Self {
1205 Self::DEFAULT
1206 }
1207}
1208#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1209#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1210#[cfg_attr(feature = "serde", serde(tag = "type"))]
1211#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1212#[repr(u32)]
1213pub enum MavArmAuthDeniedReason {
1214 #[doc = "Not a specific reason"]
1215 MAV_ARM_AUTH_DENIED_REASON_GENERIC = 0,
1216 #[doc = "Authorizer will send the error as string to GCS"]
1217 MAV_ARM_AUTH_DENIED_REASON_NONE = 1,
1218 #[doc = "At least one waypoint have a invalid value"]
1219 MAV_ARM_AUTH_DENIED_REASON_INVALID_WAYPOINT = 2,
1220 #[doc = "Timeout in the authorizer process(in case it depends on network)"]
1221 MAV_ARM_AUTH_DENIED_REASON_TIMEOUT = 3,
1222 #[doc = "Airspace of the mission in use by another vehicle, second result parameter can have the waypoint id that caused it to be denied."]
1223 MAV_ARM_AUTH_DENIED_REASON_AIRSPACE_IN_USE = 4,
1224 #[doc = "Weather is not good to fly"]
1225 MAV_ARM_AUTH_DENIED_REASON_BAD_WEATHER = 5,
1226}
1227impl MavArmAuthDeniedReason {
1228 pub const DEFAULT: Self = Self::MAV_ARM_AUTH_DENIED_REASON_GENERIC;
1229}
1230impl Default for MavArmAuthDeniedReason {
1231 fn default() -> Self {
1232 Self::DEFAULT
1233 }
1234}
1235#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1236#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1237#[cfg_attr(feature = "serde", serde(tag = "type"))]
1238#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1239#[repr(u32)]
1240pub enum MavOdidSpeedAcc {
1241 #[doc = "The speed accuracy is unknown."]
1242 MAV_ODID_SPEED_ACC_UNKNOWN = 0,
1243 #[doc = "The speed accuracy is smaller than 10 meters per second."]
1244 MAV_ODID_SPEED_ACC_10_METERS_PER_SECOND = 1,
1245 #[doc = "The speed accuracy is smaller than 3 meters per second."]
1246 MAV_ODID_SPEED_ACC_3_METERS_PER_SECOND = 2,
1247 #[doc = "The speed accuracy is smaller than 1 meters per second."]
1248 MAV_ODID_SPEED_ACC_1_METERS_PER_SECOND = 3,
1249 #[doc = "The speed accuracy is smaller than 0.3 meters per second."]
1250 MAV_ODID_SPEED_ACC_0_3_METERS_PER_SECOND = 4,
1251}
1252impl MavOdidSpeedAcc {
1253 pub const DEFAULT: Self = Self::MAV_ODID_SPEED_ACC_UNKNOWN;
1254}
1255impl Default for MavOdidSpeedAcc {
1256 fn default() -> Self {
1257 Self::DEFAULT
1258 }
1259}
1260#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1261#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1262#[cfg_attr(feature = "serde", serde(tag = "type"))]
1263#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1264#[repr(u32)]
1265pub enum FenceBreach {
1266 #[doc = "No last fence breach"]
1267 FENCE_BREACH_NONE = 0,
1268 #[doc = "Breached minimum altitude"]
1269 FENCE_BREACH_MINALT = 1,
1270 #[doc = "Breached maximum altitude"]
1271 FENCE_BREACH_MAXALT = 2,
1272 #[doc = "Breached fence boundary"]
1273 FENCE_BREACH_BOUNDARY = 3,
1274}
1275impl FenceBreach {
1276 pub const DEFAULT: Self = Self::FENCE_BREACH_NONE;
1277}
1278impl Default for FenceBreach {
1279 fn default() -> Self {
1280 Self::DEFAULT
1281 }
1282}
1283bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags for high level gimbal manager operation The first 16 bits are identical to the GIMBAL_DEVICE_FLAGS."] pub struct GimbalManagerFlags : u32 { # [doc = "Based on GIMBAL_DEVICE_FLAGS_RETRACT."] const GIMBAL_MANAGER_FLAGS_RETRACT = 1 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_NEUTRAL."] const GIMBAL_MANAGER_FLAGS_NEUTRAL = 2 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_ROLL_LOCK."] const GIMBAL_MANAGER_FLAGS_ROLL_LOCK = 4 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_PITCH_LOCK."] const GIMBAL_MANAGER_FLAGS_PITCH_LOCK = 8 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_YAW_LOCK."] const GIMBAL_MANAGER_FLAGS_YAW_LOCK = 16 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME."] const GIMBAL_MANAGER_FLAGS_YAW_IN_VEHICLE_FRAME = 32 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME."] const GIMBAL_MANAGER_FLAGS_YAW_IN_EARTH_FRAME = 64 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME."] const GIMBAL_MANAGER_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME = 128 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE."] const GIMBAL_MANAGER_FLAGS_RC_EXCLUSIVE = 256 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_RC_MIXED."] const GIMBAL_MANAGER_FLAGS_RC_MIXED = 512 ; } }
1284impl GimbalManagerFlags {
1285 pub const DEFAULT: Self = Self::GIMBAL_MANAGER_FLAGS_RETRACT;
1286}
1287impl Default for GimbalManagerFlags {
1288 fn default() -> Self {
1289 Self::DEFAULT
1290 }
1291}
1292#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1293#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1294#[cfg_attr(feature = "serde", serde(tag = "type"))]
1295#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1296#[repr(u32)]
1297#[doc = "Type of mission items being requested/sent in mission protocol."]
1298pub enum MavMissionType {
1299 #[doc = "Items are mission commands for main mission."]
1300 MAV_MISSION_TYPE_MISSION = 0,
1301 #[doc = "Specifies GeoFence area(s). Items are MAV_CMD_NAV_FENCE_ GeoFence items."]
1302 MAV_MISSION_TYPE_FENCE = 1,
1303 #[doc = "Specifies the rally points for the vehicle. Rally points are alternative RTL points. Items are MAV_CMD_NAV_RALLY_POINT rally point items."]
1304 MAV_MISSION_TYPE_RALLY = 2,
1305 #[doc = "Only used in MISSION_CLEAR_ALL to clear all mission types."]
1306 MAV_MISSION_TYPE_ALL = 255,
1307}
1308impl MavMissionType {
1309 pub const DEFAULT: Self = Self::MAV_MISSION_TYPE_MISSION;
1310}
1311impl Default for MavMissionType {
1312 fn default() -> Self {
1313 Self::DEFAULT
1314 }
1315}
1316#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1317#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1318#[cfg_attr(feature = "serde", serde(tag = "type"))]
1319#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1320#[repr(u32)]
1321#[doc = "RC type. Used in MAV_CMD_START_RX_PAIR."]
1322pub enum RcType {
1323 #[doc = "Spektrum"]
1324 RC_TYPE_SPEKTRUM = 0,
1325 #[doc = "CRSF"]
1326 RC_TYPE_CRSF = 1,
1327}
1328impl RcType {
1329 pub const DEFAULT: Self = Self::RC_TYPE_SPEKTRUM;
1330}
1331impl Default for RcType {
1332 fn default() -> Self {
1333 Self::DEFAULT
1334 }
1335}
1336#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1337#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1338#[cfg_attr(feature = "serde", serde(tag = "type"))]
1339#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1340#[repr(u32)]
1341#[doc = "Actions being taken to mitigate/prevent fence breach"]
1342pub enum FenceMitigate {
1343 #[doc = "Unknown"]
1344 FENCE_MITIGATE_UNKNOWN = 0,
1345 #[doc = "No actions being taken"]
1346 FENCE_MITIGATE_NONE = 1,
1347 #[doc = "Velocity limiting active to prevent breach"]
1348 FENCE_MITIGATE_VEL_LIMIT = 2,
1349}
1350impl FenceMitigate {
1351 pub const DEFAULT: Self = Self::FENCE_MITIGATE_UNKNOWN;
1352}
1353impl Default for FenceMitigate {
1354 fn default() -> Self {
1355 Self::DEFAULT
1356 }
1357}
1358#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1359#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1360#[cfg_attr(feature = "serde", serde(tag = "type"))]
1361#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1362#[repr(u32)]
1363#[doc = "These values define the type of firmware release. These values indicate the first version or release of this type. For example the first alpha release would be 64, the second would be 65."]
1364pub enum FirmwareVersionType {
1365 #[doc = "development release"]
1366 FIRMWARE_VERSION_TYPE_DEV = 0,
1367 #[doc = "alpha release"]
1368 FIRMWARE_VERSION_TYPE_ALPHA = 64,
1369 #[doc = "beta release"]
1370 FIRMWARE_VERSION_TYPE_BETA = 128,
1371 #[doc = "release candidate"]
1372 FIRMWARE_VERSION_TYPE_RC = 192,
1373 #[doc = "official stable release"]
1374 FIRMWARE_VERSION_TYPE_OFFICIAL = 255,
1375}
1376impl FirmwareVersionType {
1377 pub const DEFAULT: Self = Self::FIRMWARE_VERSION_TYPE_DEV;
1378}
1379impl Default for FirmwareVersionType {
1380 fn default() -> Self {
1381 Self::DEFAULT
1382 }
1383}
1384#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1385#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1386#[cfg_attr(feature = "serde", serde(tag = "type"))]
1387#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1388#[repr(u32)]
1389#[doc = "Commands to be executed by the MAV. They can be executed on user request, or as part of a mission script. If the action is used in a mission, the parameter mapping to the waypoint/mission message is as follows: Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data. NaN and INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component's current yaw or latitude rather than a specific value). See <https://mavlink.io/en/guide/xml_schema.html#MAV_CMD> for information about the structure of the MAV_CMD entries"]
1390pub enum MavCmd {
1391 #[doc = "Navigate to waypoint. This is intended for use in missions (for guided commands outside of missions use MAV_CMD_DO_REPOSITION)."]
1392 MAV_CMD_NAV_WAYPOINT = 16,
1393 #[doc = "Loiter around this waypoint an unlimited amount of time"]
1394 MAV_CMD_NAV_LOITER_UNLIM = 17,
1395 #[doc = "Loiter around this waypoint for X turns"]
1396 MAV_CMD_NAV_LOITER_TURNS = 18,
1397 #[doc = "Loiter at the specified latitude, longitude and altitude for a certain amount of time. Multicopter vehicles stop at the point (within a vehicle-specific acceptance radius). Forward-only moving vehicles (e.g. fixed-wing) circle the point with the specified radius/direction. If the Heading Required parameter (2) is non-zero forward moving aircraft will only leave the loiter circle once heading towards the next waypoint."]
1398 MAV_CMD_NAV_LOITER_TIME = 19,
1399 #[doc = "Return to launch location"]
1400 MAV_CMD_NAV_RETURN_TO_LAUNCH = 20,
1401 #[doc = "Land at location."]
1402 MAV_CMD_NAV_LAND = 21,
1403 #[doc = "Takeoff from ground / hand. Vehicles that support multiple takeoff modes (e.g. VTOL quadplane) should take off using the currently configured mode."]
1404 MAV_CMD_NAV_TAKEOFF = 22,
1405 #[doc = "Land at local position (local frame only)"]
1406 MAV_CMD_NAV_LAND_LOCAL = 23,
1407 #[doc = "Takeoff from local position (local frame only)"]
1408 MAV_CMD_NAV_TAKEOFF_LOCAL = 24,
1409 #[doc = "Vehicle following, i.e. this waypoint represents the position of a moving vehicle"]
1410 MAV_CMD_NAV_FOLLOW = 25,
1411 #[doc = "Continue on the current course and climb/descend to specified altitude. When the altitude is reached continue to the next command (i.e., don't proceed to the next command until the desired altitude is reached."]
1412 MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT = 30,
1413 #[doc = "Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, then loiter at the current position. Don't consider the navigation command complete (don't leave loiter) until the altitude has been reached. Additionally, if the Heading Required parameter is non-zero the aircraft will not leave the loiter until heading toward the next waypoint."]
1414 MAV_CMD_NAV_LOITER_TO_ALT = 31,
1415 #[doc = "Begin following a target"]
1416 MAV_CMD_DO_FOLLOW = 32,
1417 #[doc = "Reposition the MAV after a follow target command has been sent"]
1418 MAV_CMD_DO_FOLLOW_REPOSITION = 33,
1419 #[doc = "Start orbiting on the circumference of a circle defined by the parameters. Setting values to NaN/INT32_MAX (as appropriate) results in using defaults."]
1420 MAV_CMD_DO_ORBIT = 34,
1421 #[doc = "Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras."]
1422 MAV_CMD_NAV_ROI = 80,
1423 #[doc = "Control autonomous path planning on the MAV."]
1424 MAV_CMD_NAV_PATHPLANNING = 81,
1425 #[doc = "Navigate to waypoint using a spline path."]
1426 MAV_CMD_NAV_SPLINE_WAYPOINT = 82,
1427 #[doc = "Takeoff from ground using VTOL mode, and transition to forward flight with specified heading. The command should be ignored by vehicles that dont support both VTOL and fixed-wing flight (multicopters, boats,etc.)."]
1428 MAV_CMD_NAV_VTOL_TAKEOFF = 84,
1429 #[doc = "Land using VTOL mode"]
1430 MAV_CMD_NAV_VTOL_LAND = 85,
1431 #[doc = "hand control over to an external controller"]
1432 MAV_CMD_NAV_GUIDED_ENABLE = 92,
1433 #[doc = "Delay the next navigation command a number of seconds or until a specified time"]
1434 MAV_CMD_NAV_DELAY = 93,
1435 #[doc = "Descend and place payload. Vehicle moves to specified location, descends until it detects a hanging payload has reached the ground, and then releases the payload. If ground is not detected before the reaching the maximum descent value (param1), the command will complete without releasing the payload."]
1436 MAV_CMD_NAV_PAYLOAD_PLACE = 94,
1437 #[doc = "NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration"]
1438 MAV_CMD_NAV_LAST = 95,
1439 #[doc = "Delay mission state machine."]
1440 MAV_CMD_CONDITION_DELAY = 112,
1441 #[doc = "Ascend/descend to target altitude at specified rate. Delay mission state machine until desired altitude reached."]
1442 MAV_CMD_CONDITION_CHANGE_ALT = 113,
1443 #[doc = "Delay mission state machine until within desired distance of next NAV point."]
1444 MAV_CMD_CONDITION_DISTANCE = 114,
1445 #[doc = "Reach a certain target angle."]
1446 MAV_CMD_CONDITION_YAW = 115,
1447 #[doc = "NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration"]
1448 MAV_CMD_CONDITION_LAST = 159,
1449 #[doc = "Set system mode."]
1450 MAV_CMD_DO_SET_MODE = 176,
1451 #[doc = "Jump to the desired command in the mission list. Repeat this action only the specified number of times"]
1452 MAV_CMD_DO_JUMP = 177,
1453 #[doc = "Change speed and/or throttle set points. The value persists until it is overridden or there is a mode change"]
1454 MAV_CMD_DO_CHANGE_SPEED = 178,
1455 #[doc = "Sets the home position to either to the current position or a specified position. The home position is the default position that the system will return to and land on. The position is set automatically by the system during the takeoff (and may also be set using this command). Note: the current home position may be emitted in a HOME_POSITION message on request (using MAV_CMD_REQUEST_MESSAGE with param1=242)."]
1456 MAV_CMD_DO_SET_HOME = 179,
1457 #[doc = "Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter."]
1458 MAV_CMD_DO_SET_PARAMETER = 180,
1459 #[doc = "Set a relay to a condition."]
1460 MAV_CMD_DO_SET_RELAY = 181,
1461 #[doc = "Cycle a relay on and off for a desired number of cycles with a desired period."]
1462 MAV_CMD_DO_REPEAT_RELAY = 182,
1463 #[doc = "Set a servo to a desired PWM value."]
1464 MAV_CMD_DO_SET_SERVO = 183,
1465 #[doc = "Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period."]
1466 MAV_CMD_DO_REPEAT_SERVO = 184,
1467 #[doc = "0.5); the ACK should be either MAV_RESULT_FAILED or MAV_RESULT_UNSUPPORTED."]
1468 MAV_CMD_DO_FLIGHTTERMINATION = 185,
1469 #[doc = "Change altitude set point."]
1470 MAV_CMD_DO_CHANGE_ALTITUDE = 186,
1471 #[doc = "Sets actuators (e.g. servos) to a desired value. The actuator numbers are mapped to specific outputs (e.g. on any MAIN or AUX PWM or UAVCAN) using a flight-stack specific mechanism (i.e. a parameter)."]
1472 MAV_CMD_DO_SET_ACTUATOR = 187,
1473 #[doc = "Mission item to specify the start of a failsafe/landing return-path segment (the end of the segment is the next MAV_CMD_DO_LAND_START item). A vehicle that is using missions for landing (e.g. in a return mode) will join the mission on the closest path of the return-path segment (instead of MAV_CMD_DO_LAND_START or the nearest waypoint). The main use case is to minimize the failsafe flight path in corridor missions, where the inbound/outbound paths are constrained (by geofences) to the same particular path. The MAV_CMD_NAV_RETURN_PATH_START would be placed at the start of the return path. If a failsafe occurs on the outbound path the vehicle will move to the nearest point on the return path (which is parallel for this kind of mission), effectively turning round and following the shortest path to landing. If a failsafe occurs on the inbound path the vehicle is already on the return segment and will continue to landing. The Latitude/Longitude/Altitude are optional, and may be set to 0 if not needed. If specified, the item defines the waypoint at which the return segment starts. If sent using as a command, the vehicle will perform a mission landing (using the land segment if defined) or reject the command if mission landings are not supported, or no mission landing is defined. When used as a command any position information in the command is ignored."]
1474 MAV_CMD_DO_RETURN_PATH_START = 188,
1475 #[doc = "Mission item to mark the start of a mission landing pattern, or a command to land with a mission landing pattern. When used in a mission, this is a marker for the start of a sequence of mission items that represent a landing pattern. It should be followed by a navigation item that defines the first waypoint of the landing sequence. The start marker positional params are used only for selecting what landing pattern to use if several are defined in the mission (the selected pattern will be the one with the marker position that is closest to the vehicle when a landing is commanded). If the marker item position has zero-values for latitude, longitude, and altitude, then landing pattern selection is instead based on the position of the first waypoint in the landing sequence. \t When sent as a command it triggers a landing using a mission landing pattern. \t The location parameters are not used in this case, and should be set to 0."]
1476 MAV_CMD_DO_LAND_START = 189,
1477 #[doc = "Mission command to perform a landing from a rally point."]
1478 MAV_CMD_DO_RALLY_LAND = 190,
1479 #[doc = "Mission command to safely abort an autonomous landing."]
1480 MAV_CMD_DO_GO_AROUND = 191,
1481 #[doc = "Reposition the vehicle to a specific WGS84 global position. This command is intended for guided commands (for missions use MAV_CMD_NAV_WAYPOINT instead)."]
1482 MAV_CMD_DO_REPOSITION = 192,
1483 #[doc = "If in a GPS controlled position mode, hold the current position or continue."]
1484 MAV_CMD_DO_PAUSE_CONTINUE = 193,
1485 #[doc = "Set moving direction to forward or reverse."]
1486 MAV_CMD_DO_SET_REVERSE = 194,
1487 #[doc = "Sets the region of interest (ROI) to a location. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal is not to react to this message."]
1488 MAV_CMD_DO_SET_ROI_LOCATION = 195,
1489 #[doc = "Sets the region of interest (ROI) to be toward next waypoint, with optional pitch/roll/yaw offset. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal device is not to react to this message."]
1490 MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET = 196,
1491 #[doc = "Cancels any previous ROI command returning the vehicle/sensors to default flight characteristics. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal device is not to react to this message. After this command the gimbal manager should go back to manual input if available, and otherwise assume a neutral position."]
1492 MAV_CMD_DO_SET_ROI_NONE = 197,
1493 #[doc = "Mount tracks system with specified system ID. Determination of target vehicle position may be done with GLOBAL_POSITION_INT or any other means. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal device is not to react to this message."]
1494 MAV_CMD_DO_SET_ROI_SYSID = 198,
1495 #[doc = "Control onboard camera system."]
1496 MAV_CMD_DO_CONTROL_VIDEO = 200,
1497 #[doc = "Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras."]
1498 MAV_CMD_DO_SET_ROI = 201,
1499 #[doc = "Configure digital camera. This is a fallback message for systems that have not yet implemented PARAM_EXT_XXX messages and camera definition files (see <https://mavlink.io/en/services/camera_def.html> )."]
1500 MAV_CMD_DO_DIGICAM_CONFIGURE = 202,
1501 #[doc = "Control digital camera. This is a fallback message for systems that have not yet implemented PARAM_EXT_XXX messages and camera definition files (see <https://mavlink.io/en/services/camera_def.html> )."]
1502 MAV_CMD_DO_DIGICAM_CONTROL = 203,
1503 #[doc = "Mission command to configure a camera or antenna mount"]
1504 MAV_CMD_DO_MOUNT_CONFIGURE = 204,
1505 #[doc = "Mission command to control a camera or antenna mount"]
1506 MAV_CMD_DO_MOUNT_CONTROL = 205,
1507 #[doc = "Mission command to set camera trigger distance for this flight. The camera is triggered each time this distance is exceeded. This command can also be used to set the shutter integration time for the camera."]
1508 MAV_CMD_DO_SET_CAM_TRIGG_DIST = 206,
1509 #[doc = "Enable the geofence. This can be used in a mission or via the command protocol. The persistence/lifetime of the setting is undefined. Depending on flight stack implementation it may persist until superseded, or it may revert to a system default at the end of a mission. Flight stacks typically reset the setting to system defaults on reboot."]
1510 MAV_CMD_DO_FENCE_ENABLE = 207,
1511 #[doc = "Mission item/command to release a parachute or enable/disable auto release."]
1512 MAV_CMD_DO_PARACHUTE = 208,
1513 #[doc = "Command to perform motor test."]
1514 MAV_CMD_DO_MOTOR_TEST = 209,
1515 #[doc = "Change to/from inverted flight."]
1516 MAV_CMD_DO_INVERTED_FLIGHT = 210,
1517 #[doc = "Mission command to operate a gripper."]
1518 MAV_CMD_DO_GRIPPER = 211,
1519 #[doc = "Enable/disable autotune."]
1520 MAV_CMD_DO_AUTOTUNE_ENABLE = 212,
1521 #[doc = "Sets a desired vehicle turn angle and speed change."]
1522 MAV_CMD_NAV_SET_YAW_SPEED = 213,
1523 #[doc = "Mission command to set camera trigger interval for this flight. If triggering is enabled, the camera is triggered each time this interval expires. This command can also be used to set the shutter integration time for the camera."]
1524 MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL = 214,
1525 #[doc = "Mission command to control a camera or antenna mount, using a quaternion as reference."]
1526 MAV_CMD_DO_MOUNT_CONTROL_QUAT = 220,
1527 #[doc = "set id of master controller"]
1528 MAV_CMD_DO_GUIDED_MASTER = 221,
1529 #[doc = "Set limits for external control"]
1530 MAV_CMD_DO_GUIDED_LIMITS = 222,
1531 #[doc = "Control vehicle engine. This is interpreted by the vehicles engine controller to change the target engine state. It is intended for vehicles with internal combustion engines"]
1532 MAV_CMD_DO_ENGINE_CONTROL = 223,
1533 #[doc = "Set the mission item with sequence number seq as the current item and emit MISSION_CURRENT (whether or not the mission number changed). If a mission is currently being executed, the system will continue to this new mission item on the shortest path, skipping any intermediate mission items. \t Note that mission jump repeat counters are not reset unless param2 is set (see MAV_CMD_DO_JUMP param2). This command may trigger a mission state-machine change on some systems: for example from MISSION_STATE_NOT_STARTED or MISSION_STATE_PAUSED to MISSION_STATE_ACTIVE. If the system is in mission mode, on those systems this command might therefore start, restart or resume the mission. If the system is not in mission mode this command must not trigger a switch to mission mode. The mission may be \"reset\" using param2. Resetting sets jump counters to initial values (to reset counters without changing the current mission item set the param1 to `-1`). Resetting also explicitly changes a mission state of MISSION_STATE_COMPLETE to MISSION_STATE_PAUSED or MISSION_STATE_ACTIVE, potentially allowing it to resume when it is (next) in a mission mode. \t The command will ACK with MAV_RESULT_FAILED if the sequence number is out of range (including if there is no mission item)."]
1534 MAV_CMD_DO_SET_MISSION_CURRENT = 224,
1535 #[doc = "NOP - This command is only used to mark the upper limit of the DO commands in the enumeration"]
1536 MAV_CMD_DO_LAST = 240,
1537 #[doc = "Trigger calibration. This command will be only accepted if in pre-flight mode. Except for Temperature Calibration, only one sensor should be set in a single message and all others should be zero."]
1538 MAV_CMD_PREFLIGHT_CALIBRATION = 241,
1539 #[doc = "Set sensor offsets. This command will be only accepted if in pre-flight mode."]
1540 MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS = 242,
1541 #[doc = "Trigger UAVCAN configuration (actuator ID assignment and direction mapping). Note that this maps to the legacy UAVCAN v0 function UAVCAN_ENUMERATE, which is intended to be executed just once during initial vehicle configuration (it is not a normal pre-flight command and has been poorly named)."]
1542 MAV_CMD_PREFLIGHT_UAVCAN = 243,
1543 #[doc = "Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode."]
1544 MAV_CMD_PREFLIGHT_STORAGE = 245,
1545 #[doc = "Request the reboot or shutdown of system components."]
1546 MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN = 246,
1547 #[doc = "Override current mission with command to pause mission, pause mission and move to position, continue/resume mission. When param 1 indicates that the mission is paused (MAV_GOTO_DO_HOLD), param 2 defines whether it holds in place or moves to another position."]
1548 MAV_CMD_OVERRIDE_GOTO = 252,
1549 #[doc = "Mission command to set a Camera Auto Mount Pivoting Oblique Survey (Replaces CAM_TRIGG_DIST for this purpose). The camera is triggered each time this distance is exceeded, then the mount moves to the next position. Params 4~6 set-up the angle limits and number of positions for oblique survey, where mount-enabled vehicles automatically roll the camera between shots to emulate an oblique camera setup (providing an increased HFOV). This command can also be used to set the shutter integration time for the camera."]
1550 MAV_CMD_OBLIQUE_SURVEY = 260,
1551 #[doc = "Enable the specified standard MAVLink mode. If the specified mode is not supported, the vehicle should ACK with MAV_RESULT_FAILED. See <https://mavlink.io/en/services/standard_modes.html>"]
1552 MAV_CMD_DO_SET_STANDARD_MODE = 262,
1553 #[doc = "start running a mission"]
1554 MAV_CMD_MISSION_START = 300,
1555 #[doc = "Actuator testing command. This is similar to MAV_CMD_DO_MOTOR_TEST but operates on the level of output functions, i.e. it is possible to test Motor1 independent from which output it is configured on. Autopilots must NACK this command with MAV_RESULT_TEMPORARILY_REJECTED while armed."]
1556 MAV_CMD_ACTUATOR_TEST = 310,
1557 #[doc = "Actuator configuration command."]
1558 MAV_CMD_CONFIGURE_ACTUATOR = 311,
1559 #[doc = "Arms / Disarms a component"]
1560 MAV_CMD_COMPONENT_ARM_DISARM = 400,
1561 #[doc = "Instructs a target system to run pre-arm checks. This allows preflight checks to be run on demand, which may be useful on systems that normally run them at low rate, or which do not trigger checks when the armable state might have changed. This command should return MAV_RESULT_ACCEPTED if it will run the checks. The results of the checks are usually then reported in SYS_STATUS messages (this is system-specific). The command should return MAV_RESULT_TEMPORARILY_REJECTED if the system is already armed."]
1562 MAV_CMD_RUN_PREARM_CHECKS = 401,
1563 #[doc = "Turns illuminators ON/OFF. An illuminator is a light source that is used for lighting up dark areas external to the system: e.g. a torch or searchlight (as opposed to a light source for illuminating the system itself, e.g. an indicator light)."]
1564 MAV_CMD_ILLUMINATOR_ON_OFF = 405,
1565 #[doc = "Configures illuminator settings. An illuminator is a light source that is used for lighting up dark areas external to the system: e.g. a torch or searchlight (as opposed to a light source for illuminating the system itself, e.g. an indicator light)."]
1566 MAV_CMD_DO_ILLUMINATOR_CONFIGURE = 406,
1567 #[doc = "Request the home position from the vehicle. \t The vehicle will ACK the command and then emit the HOME_POSITION message."]
1568 MAV_CMD_GET_HOME_POSITION = 410,
1569 #[doc = "Inject artificial failure for testing purposes. Note that autopilots should implement an additional protection before accepting this command such as a specific param setting."]
1570 MAV_CMD_INJECT_FAILURE = 420,
1571 #[doc = "Starts receiver pairing."]
1572 MAV_CMD_START_RX_PAIR = 500,
1573 #[doc = "Request the interval between messages for a particular MAVLink message ID. The receiver should ACK the command and then emit its response in a MESSAGE_INTERVAL message."]
1574 MAV_CMD_GET_MESSAGE_INTERVAL = 510,
1575 #[doc = "Set the interval between messages for a particular MAVLink message ID. This interface replaces REQUEST_DATA_STREAM."]
1576 MAV_CMD_SET_MESSAGE_INTERVAL = 511,
1577 #[doc = "Request the target system(s) emit a single instance of a specified message (i.e. a \"one-shot\" version of MAV_CMD_SET_MESSAGE_INTERVAL)."]
1578 MAV_CMD_REQUEST_MESSAGE = 512,
1579 #[doc = "Request MAVLink protocol version compatibility. All receivers should ACK the command and then emit their capabilities in an PROTOCOL_VERSION message"]
1580 MAV_CMD_REQUEST_PROTOCOL_VERSION = 519,
1581 #[doc = "Request autopilot capabilities. The receiver should ACK the command and then emit its capabilities in an AUTOPILOT_VERSION message"]
1582 MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES = 520,
1583 #[doc = "Request camera information (CAMERA_INFORMATION)."]
1584 MAV_CMD_REQUEST_CAMERA_INFORMATION = 521,
1585 #[doc = "Request camera settings (CAMERA_SETTINGS)."]
1586 MAV_CMD_REQUEST_CAMERA_SETTINGS = 522,
1587 #[doc = "Request storage information (STORAGE_INFORMATION). Use the command's target_component to target a specific component's storage."]
1588 MAV_CMD_REQUEST_STORAGE_INFORMATION = 525,
1589 #[doc = "Format a storage medium. Once format is complete, a STORAGE_INFORMATION message is sent. Use the command's target_component to target a specific component's storage."]
1590 MAV_CMD_STORAGE_FORMAT = 526,
1591 #[doc = "Request camera capture status (CAMERA_CAPTURE_STATUS)"]
1592 MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS = 527,
1593 #[doc = "Request flight information (FLIGHT_INFORMATION)"]
1594 MAV_CMD_REQUEST_FLIGHT_INFORMATION = 528,
1595 #[doc = "Reset all camera settings to Factory Default"]
1596 MAV_CMD_RESET_CAMERA_SETTINGS = 529,
1597 #[doc = "Set camera running mode. Use NaN for reserved values. GCS will send a MAV_CMD_REQUEST_VIDEO_STREAM_STATUS command after a mode change if the camera supports video streaming."]
1598 MAV_CMD_SET_CAMERA_MODE = 530,
1599 #[doc = "Set camera zoom. Camera must respond with a CAMERA_SETTINGS message (on success)."]
1600 MAV_CMD_SET_CAMERA_ZOOM = 531,
1601 #[doc = "Set camera focus. Camera must respond with a CAMERA_SETTINGS message (on success)."]
1602 MAV_CMD_SET_CAMERA_FOCUS = 532,
1603 #[doc = "Set that a particular storage is the preferred location for saving photos, videos, and/or other media (e.g. to set that an SD card is used for storing videos). There can only be one preferred save location for each particular media type: setting a media usage flag will clear/reset that same flag if set on any other storage. If no flag is set the system should use its default storage. A target system can choose to always use default storage, in which case it should ACK the command with MAV_RESULT_UNSUPPORTED. A target system can choose to not allow a particular storage to be set as preferred storage, in which case it should ACK the command with MAV_RESULT_DENIED."]
1604 MAV_CMD_SET_STORAGE_USAGE = 533,
1605 #[doc = "Set camera source. Changes the camera's active sources on cameras with multiple image sensors."]
1606 MAV_CMD_SET_CAMERA_SOURCE = 534,
1607 #[doc = "Tagged jump target. Can be jumped to with MAV_CMD_DO_JUMP_TAG."]
1608 MAV_CMD_JUMP_TAG = 600,
1609 #[doc = "Jump to the matching tag in the mission list. Repeat this action for the specified number of times. A mission should contain a single matching tag for each jump. If this is not the case then a jump to a missing tag should complete the mission, and a jump where there are multiple matching tags should always select the one with the lowest mission sequence number."]
1610 MAV_CMD_DO_JUMP_TAG = 601,
1611 #[doc = "Set gimbal manager pitch/yaw setpoints (low rate command). It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. Note: only the gimbal manager will react to this command - it will be ignored by a gimbal device. Use GIMBAL_MANAGER_SET_PITCHYAW if you need to stream pitch/yaw setpoints at higher rate."]
1612 MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW = 1000,
1613 #[doc = "Gimbal configuration to set which sysid/compid is in primary and secondary control."]
1614 MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE = 1001,
1615 #[doc = "Start image capture sequence. CAMERA_IMAGE_CAPTURED must be emitted after each capture. Param1 (id) may be used to specify the target camera: 0: all cameras, 1 to 6: autopilot-connected cameras, 7-255: MAVLink camera component ID. It is needed in order to target specific cameras connected to the autopilot, or specific sensors in a multi-sensor camera (neither of which have a distinct MAVLink component ID). It is also needed to specify the target camera in missions. When used in a mission, an autopilot should execute the MAV_CMD for a specified local camera (param1 = 1-6), or resend it as a command if it is intended for a MAVLink camera (param1 = 7 - 255), setting the command's target_component as the param1 value (and setting param1 in the command to zero). If the param1 is 0 the autopilot should do both. When sent in a command the target MAVLink address is set using target_component. If addressed specifically to an autopilot: param1 should be used in the same way as it is for missions (though command should NACK with MAV_RESULT_DENIED if a specified local camera does not exist). If addressed to a MAVLink camera, param 1 can be used to address all cameras (0), or to separately address 1 to 7 individual sensors. Other values should be NACKed with MAV_RESULT_DENIED. If the command is broadcast (target_component is 0) then param 1 should be set to 0 (any other value should be NACKED with MAV_RESULT_DENIED). An autopilot would trigger any local cameras and forward the command to all channels."]
1616 MAV_CMD_IMAGE_START_CAPTURE = 2000,
1617 #[doc = "Stop image capture sequence. Param1 (id) may be used to specify the target camera: 0: all cameras, 1 to 6: autopilot-connected cameras, 7-255: MAVLink camera component ID. It is needed in order to target specific cameras connected to the autopilot, or specific sensors in a multi-sensor camera (neither of which have a distinct MAVLink component ID). It is also needed to specify the target camera in missions. When used in a mission, an autopilot should execute the MAV_CMD for a specified local camera (param1 = 1-6), or resend it as a command if it is intended for a MAVLink camera (param1 = 7 - 255), setting the command's target_component as the param1 value (and setting param1 in the command to zero). If the param1 is 0 the autopilot should do both. When sent in a command the target MAVLink address is set using target_component. If addressed specifically to an autopilot: param1 should be used in the same way as it is for missions (though command should NACK with MAV_RESULT_DENIED if a specified local camera does not exist). If addressed to a MAVLink camera, param1 can be used to address all cameras (0), or to separately address 1 to 7 individual sensors. Other values should be NACKed with MAV_RESULT_DENIED. If the command is broadcast (target_component is 0) then param 1 should be set to 0 (any other value should be NACKED with MAV_RESULT_DENIED). An autopilot would trigger any local cameras and forward the command to all channels."]
1618 MAV_CMD_IMAGE_STOP_CAPTURE = 2001,
1619 #[doc = "Re-request a CAMERA_IMAGE_CAPTURED message."]
1620 MAV_CMD_REQUEST_CAMERA_IMAGE_CAPTURE = 2002,
1621 #[doc = "Enable or disable on-board camera triggering system."]
1622 MAV_CMD_DO_TRIGGER_CONTROL = 2003,
1623 #[doc = "If the camera supports point visual tracking (CAMERA_CAP_FLAGS_HAS_TRACKING_POINT is set), this command allows to initiate the tracking."]
1624 MAV_CMD_CAMERA_TRACK_POINT = 2004,
1625 #[doc = "If the camera supports rectangle visual tracking (CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE is set), this command allows to initiate the tracking."]
1626 MAV_CMD_CAMERA_TRACK_RECTANGLE = 2005,
1627 #[doc = "Stops ongoing tracking."]
1628 MAV_CMD_CAMERA_STOP_TRACKING = 2010,
1629 #[doc = "Starts video capture (recording)."]
1630 MAV_CMD_VIDEO_START_CAPTURE = 2500,
1631 #[doc = "Stop the current video capture (recording)."]
1632 MAV_CMD_VIDEO_STOP_CAPTURE = 2501,
1633 #[doc = "Start video streaming"]
1634 MAV_CMD_VIDEO_START_STREAMING = 2502,
1635 #[doc = "Stop the given video stream"]
1636 MAV_CMD_VIDEO_STOP_STREAMING = 2503,
1637 #[doc = "Request video stream information (VIDEO_STREAM_INFORMATION)"]
1638 MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION = 2504,
1639 #[doc = "Request video stream status (VIDEO_STREAM_STATUS)"]
1640 MAV_CMD_REQUEST_VIDEO_STREAM_STATUS = 2505,
1641 #[doc = "Request to start streaming logging data over MAVLink (see also LOGGING_DATA message)"]
1642 MAV_CMD_LOGGING_START = 2510,
1643 #[doc = "Request to stop streaming log data over MAVLink"]
1644 MAV_CMD_LOGGING_STOP = 2511,
1645 MAV_CMD_AIRFRAME_CONFIGURATION = 2520,
1646 #[doc = "Request to start/stop transmitting over the high latency telemetry"]
1647 MAV_CMD_CONTROL_HIGH_LATENCY = 2600,
1648 #[doc = "Create a panorama at the current position"]
1649 MAV_CMD_PANORAMA_CREATE = 2800,
1650 #[doc = "Request VTOL transition"]
1651 MAV_CMD_DO_VTOL_TRANSITION = 3000,
1652 #[doc = "Request authorization to arm the vehicle to a external entity, the arm authorizer is responsible to request all data that is needs from the vehicle before authorize or deny the request. \t\tIf approved the COMMAND_ACK message progress field should be set with period of time that this authorization is valid in seconds. \t\tIf the authorization is denied COMMAND_ACK.result_param2 should be set with one of the reasons in ARM_AUTH_DENIED_REASON."]
1653 MAV_CMD_ARM_AUTHORIZATION_REQUEST = 3001,
1654 #[doc = "This command sets the submode to standard guided when vehicle is in guided mode. The vehicle holds position and altitude and the user can input the desired velocities along all three axes."]
1655 MAV_CMD_SET_GUIDED_SUBMODE_STANDARD = 4000,
1656 #[doc = "This command sets submode circle when vehicle is in guided mode. Vehicle flies along a circle facing the center of the circle. The user can input the velocity along the circle and change the radius. If no input is given the vehicle will hold position."]
1657 MAV_CMD_SET_GUIDED_SUBMODE_CIRCLE = 4001,
1658 #[doc = "Delay mission state machine until gate has been reached."]
1659 MAV_CMD_CONDITION_GATE = 4501,
1660 #[doc = "Fence return point (there can only be one such point in a geofence definition). If rally points are supported they should be used instead."]
1661 MAV_CMD_NAV_FENCE_RETURN_POINT = 5000,
1662 #[doc = "Fence vertex for an inclusion polygon (the polygon must not be self-intersecting). The vehicle must stay within this area. Minimum of 3 vertices required. The vertices for a polygon must be sent sequentially, each with param1 set to the total number of vertices in the polygon."]
1663 MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION = 5001,
1664 #[doc = "Fence vertex for an exclusion polygon (the polygon must not be self-intersecting). The vehicle must stay outside this area. Minimum of 3 vertices required. The vertices for a polygon must be sent sequentially, each with param1 set to the total number of vertices in the polygon."]
1665 MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION = 5002,
1666 #[doc = "Circular fence area. The vehicle must stay inside this area."]
1667 MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION = 5003,
1668 #[doc = "Circular fence area. The vehicle must stay outside this area."]
1669 MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION = 5004,
1670 #[doc = "Rally point. You can have multiple rally points defined."]
1671 MAV_CMD_NAV_RALLY_POINT = 5100,
1672 #[doc = "Commands the vehicle to respond with a sequence of messages UAVCAN_NODE_INFO, one message per every UAVCAN node that is online. Note that some of the response messages can be lost, which the receiver can detect easily by checking whether every received UAVCAN_NODE_STATUS has a matching message UAVCAN_NODE_INFO received earlier; if not, this command should be sent again in order to request re-transmission of the node information messages."]
1673 MAV_CMD_UAVCAN_GET_NODE_INFO = 5200,
1674 #[doc = "Change state of safety switch."]
1675 MAV_CMD_DO_SET_SAFETY_SWITCH_STATE = 5300,
1676 #[doc = "Trigger the start of an ADSB-out IDENT. This should only be used when requested to do so by an Air Traffic Controller in controlled airspace. This starts the IDENT which is then typically held for 18 seconds by the hardware per the Mode A, C, and S transponder spec."]
1677 MAV_CMD_DO_ADSB_OUT_IDENT = 10001,
1678 #[doc = "Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity."]
1679 MAV_CMD_PAYLOAD_PREPARE_DEPLOY = 30001,
1680 #[doc = "Control the payload deployment."]
1681 MAV_CMD_PAYLOAD_CONTROL_DEPLOY = 30002,
1682 #[doc = "Magnetometer calibration based on provided known yaw. This allows for fast calibration using WMM field tables in the vehicle, given only the known yaw of the vehicle. If Latitude and longitude are both zero then use the current vehicle location."]
1683 MAV_CMD_FIXED_MAG_CAL_YAW = 42006,
1684 #[doc = "Command to operate winch."]
1685 MAV_CMD_DO_WINCH = 42600,
1686 #[doc = "Provide an external position estimate for use when dead-reckoning. This is meant to be used for occasional position resets that may be provided by a external system such as a remote pilot using landmarks over a video link."]
1687 MAV_CMD_EXTERNAL_POSITION_ESTIMATE = 43003,
1688 #[doc = "User defined waypoint item. Ground Station will show the Vehicle as flying through this item."]
1689 MAV_CMD_WAYPOINT_USER_1 = 31000,
1690 #[doc = "User defined waypoint item. Ground Station will show the Vehicle as flying through this item."]
1691 MAV_CMD_WAYPOINT_USER_2 = 31001,
1692 #[doc = "User defined waypoint item. Ground Station will show the Vehicle as flying through this item."]
1693 MAV_CMD_WAYPOINT_USER_3 = 31002,
1694 #[doc = "User defined waypoint item. Ground Station will show the Vehicle as flying through this item."]
1695 MAV_CMD_WAYPOINT_USER_4 = 31003,
1696 #[doc = "User defined waypoint item. Ground Station will show the Vehicle as flying through this item."]
1697 MAV_CMD_WAYPOINT_USER_5 = 31004,
1698 #[doc = "User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item."]
1699 MAV_CMD_SPATIAL_USER_1 = 31005,
1700 #[doc = "User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item."]
1701 MAV_CMD_SPATIAL_USER_2 = 31006,
1702 #[doc = "User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item."]
1703 MAV_CMD_SPATIAL_USER_3 = 31007,
1704 #[doc = "User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item."]
1705 MAV_CMD_SPATIAL_USER_4 = 31008,
1706 #[doc = "User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item."]
1707 MAV_CMD_SPATIAL_USER_5 = 31009,
1708 #[doc = "User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item."]
1709 MAV_CMD_USER_1 = 31010,
1710 #[doc = "User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item."]
1711 MAV_CMD_USER_2 = 31011,
1712 #[doc = "User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item."]
1713 MAV_CMD_USER_3 = 31012,
1714 #[doc = "User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item."]
1715 MAV_CMD_USER_4 = 31013,
1716 #[doc = "User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item."]
1717 MAV_CMD_USER_5 = 31014,
1718 #[doc = "Request forwarding of CAN packets from the given CAN bus to this component. CAN Frames are sent using CAN_FRAME and CANFD_FRAME messages"]
1719 MAV_CMD_CAN_FORWARD = 32000,
1720}
1721impl MavCmd {
1722 pub const DEFAULT: Self = Self::MAV_CMD_NAV_WAYPOINT;
1723}
1724impl Default for MavCmd {
1725 fn default() -> Self {
1726 Self::DEFAULT
1727 }
1728}
1729bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Smart battery supply status/fault flags (bitmask) for health indication. The battery must also report either MAV_BATTERY_CHARGE_STATE_FAILED or MAV_BATTERY_CHARGE_STATE_UNHEALTHY if any of these are set."] pub struct MavBatteryFault : u32 { # [doc = "Battery has deep discharged."] const MAV_BATTERY_FAULT_DEEP_DISCHARGE = 1 ; # [doc = "Voltage spikes."] const MAV_BATTERY_FAULT_SPIKES = 2 ; # [doc = "One or more cells have failed. Battery should also report MAV_BATTERY_CHARGE_STATE_FAILE (and should not be used)."] const MAV_BATTERY_FAULT_CELL_FAIL = 4 ; # [doc = "Over-current fault."] const MAV_BATTERY_FAULT_OVER_CURRENT = 8 ; # [doc = "Over-temperature fault."] const MAV_BATTERY_FAULT_OVER_TEMPERATURE = 16 ; # [doc = "Under-temperature fault."] const MAV_BATTERY_FAULT_UNDER_TEMPERATURE = 32 ; # [doc = "Vehicle voltage is not compatible with this battery (batteries on same power rail should have similar voltage)."] const MAV_BATTERY_FAULT_INCOMPATIBLE_VOLTAGE = 64 ; # [doc = "Battery firmware is not compatible with current autopilot firmware."] const MAV_BATTERY_FAULT_INCOMPATIBLE_FIRMWARE = 128 ; # [doc = "Battery is not compatible due to cell configuration (e.g. 5s1p when vehicle requires 6s)."] const BATTERY_FAULT_INCOMPATIBLE_CELLS_CONFIGURATION = 256 ; } }
1730impl MavBatteryFault {
1731 pub const DEFAULT: Self = Self::MAV_BATTERY_FAULT_DEEP_DISCHARGE;
1732}
1733impl Default for MavBatteryFault {
1734 fn default() -> Self {
1735 Self::DEFAULT
1736 }
1737}
1738bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Camera tracking target data (shows where tracked target is within image)"] pub struct CameraTrackingTargetData : u8 { # [doc = "Target data embedded in image data (proprietary)"] const CAMERA_TRACKING_TARGET_DATA_EMBEDDED = 1 ; # [doc = "Target data rendered in image"] const CAMERA_TRACKING_TARGET_DATA_RENDERED = 2 ; # [doc = "Target data within status message (Point or Rectangle)"] const CAMERA_TRACKING_TARGET_DATA_IN_STATUS = 4 ; } }
1739impl CameraTrackingTargetData {
1740 pub const DEFAULT: Self = Self::CAMERA_TRACKING_TARGET_DATA_EMBEDDED;
1741}
1742impl Default for CameraTrackingTargetData {
1743 fn default() -> Self {
1744 Self::DEFAULT
1745 }
1746}
1747#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1748#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1749#[cfg_attr(feature = "serde", serde(tag = "type"))]
1750#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1751#[repr(u32)]
1752pub enum MavOdidVerAcc {
1753 #[doc = "The vertical accuracy is unknown."]
1754 MAV_ODID_VER_ACC_UNKNOWN = 0,
1755 #[doc = "The vertical accuracy is smaller than 150 meter."]
1756 MAV_ODID_VER_ACC_150_METER = 1,
1757 #[doc = "The vertical accuracy is smaller than 45 meter."]
1758 MAV_ODID_VER_ACC_45_METER = 2,
1759 #[doc = "The vertical accuracy is smaller than 25 meter."]
1760 MAV_ODID_VER_ACC_25_METER = 3,
1761 #[doc = "The vertical accuracy is smaller than 10 meter."]
1762 MAV_ODID_VER_ACC_10_METER = 4,
1763 #[doc = "The vertical accuracy is smaller than 3 meter."]
1764 MAV_ODID_VER_ACC_3_METER = 5,
1765 #[doc = "The vertical accuracy is smaller than 1 meter."]
1766 MAV_ODID_VER_ACC_1_METER = 6,
1767}
1768impl MavOdidVerAcc {
1769 pub const DEFAULT: Self = Self::MAV_ODID_VER_ACC_UNKNOWN;
1770}
1771impl Default for MavOdidVerAcc {
1772 fn default() -> Self {
1773 Self::DEFAULT
1774 }
1775}
1776#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1777#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1778#[cfg_attr(feature = "serde", serde(tag = "type"))]
1779#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1780#[repr(u32)]
1781#[doc = "Enumeration for battery charge states."]
1782pub enum MavBatteryChargeState {
1783 #[doc = "Low battery state is not provided"]
1784 MAV_BATTERY_CHARGE_STATE_UNDEFINED = 0,
1785 #[doc = "Battery is not in low state. Normal operation."]
1786 MAV_BATTERY_CHARGE_STATE_OK = 1,
1787 #[doc = "Battery state is low, warn and monitor close."]
1788 MAV_BATTERY_CHARGE_STATE_LOW = 2,
1789 #[doc = "Battery state is critical, return or abort immediately."]
1790 MAV_BATTERY_CHARGE_STATE_CRITICAL = 3,
1791 #[doc = "Battery state is too low for ordinary abort sequence. Perform fastest possible emergency stop to prevent damage."]
1792 MAV_BATTERY_CHARGE_STATE_EMERGENCY = 4,
1793 #[doc = "Battery failed, damage unavoidable. Possible causes (faults) are listed in MAV_BATTERY_FAULT."]
1794 MAV_BATTERY_CHARGE_STATE_FAILED = 5,
1795 #[doc = "Battery is diagnosed to be defective or an error occurred, usage is discouraged / prohibited. Possible causes (faults) are listed in MAV_BATTERY_FAULT."]
1796 MAV_BATTERY_CHARGE_STATE_UNHEALTHY = 6,
1797 #[doc = "Battery is charging."]
1798 MAV_BATTERY_CHARGE_STATE_CHARGING = 7,
1799}
1800impl MavBatteryChargeState {
1801 pub const DEFAULT: Self = Self::MAV_BATTERY_CHARGE_STATE_UNDEFINED;
1802}
1803impl Default for MavBatteryChargeState {
1804 fn default() -> Self {
1805 Self::DEFAULT
1806 }
1807}
1808#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1809#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1810#[cfg_attr(feature = "serde", serde(tag = "type"))]
1811#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1812#[repr(u32)]
1813#[doc = "Specifies the datatype of a MAVLink parameter."]
1814pub enum MavParamType {
1815 #[doc = "8-bit unsigned integer"]
1816 MAV_PARAM_TYPE_UINT8 = 1,
1817 #[doc = "8-bit signed integer"]
1818 MAV_PARAM_TYPE_INT8 = 2,
1819 #[doc = "16-bit unsigned integer"]
1820 MAV_PARAM_TYPE_UINT16 = 3,
1821 #[doc = "16-bit signed integer"]
1822 MAV_PARAM_TYPE_INT16 = 4,
1823 #[doc = "32-bit unsigned integer"]
1824 MAV_PARAM_TYPE_UINT32 = 5,
1825 #[doc = "32-bit signed integer"]
1826 MAV_PARAM_TYPE_INT32 = 6,
1827 #[doc = "64-bit unsigned integer"]
1828 MAV_PARAM_TYPE_UINT64 = 7,
1829 #[doc = "64-bit signed integer"]
1830 MAV_PARAM_TYPE_INT64 = 8,
1831 #[doc = "32-bit floating-point"]
1832 MAV_PARAM_TYPE_REAL32 = 9,
1833 #[doc = "64-bit floating-point"]
1834 MAV_PARAM_TYPE_REAL64 = 10,
1835}
1836impl MavParamType {
1837 pub const DEFAULT: Self = Self::MAV_PARAM_TYPE_UINT8;
1838}
1839impl Default for MavParamType {
1840 fn default() -> Self {
1841 Self::DEFAULT
1842 }
1843}
1844#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1845#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1846#[cfg_attr(feature = "serde", serde(tag = "type"))]
1847#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1848#[repr(u32)]
1849#[doc = "Possible actions an aircraft can take to avoid a collision."]
1850pub enum MavCollisionAction {
1851 #[doc = "Ignore any potential collisions"]
1852 MAV_COLLISION_ACTION_NONE = 0,
1853 #[doc = "Report potential collision"]
1854 MAV_COLLISION_ACTION_REPORT = 1,
1855 #[doc = "Ascend or Descend to avoid threat"]
1856 MAV_COLLISION_ACTION_ASCEND_OR_DESCEND = 2,
1857 #[doc = "Move horizontally to avoid threat"]
1858 MAV_COLLISION_ACTION_MOVE_HORIZONTALLY = 3,
1859 #[doc = "Aircraft to move perpendicular to the collision's velocity vector"]
1860 MAV_COLLISION_ACTION_MOVE_PERPENDICULAR = 4,
1861 #[doc = "Aircraft to fly directly back to its launch point"]
1862 MAV_COLLISION_ACTION_RTL = 5,
1863 #[doc = "Aircraft to stop in place"]
1864 MAV_COLLISION_ACTION_HOVER = 6,
1865}
1866impl MavCollisionAction {
1867 pub const DEFAULT: Self = Self::MAV_COLLISION_ACTION_NONE;
1868}
1869impl Default for MavCollisionAction {
1870 fn default() -> Self {
1871 Self::DEFAULT
1872 }
1873}
1874#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1875#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1876#[cfg_attr(feature = "serde", serde(tag = "type"))]
1877#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1878#[repr(u32)]
1879#[doc = "Parachute actions. Trigger release and enable/disable auto-release."]
1880pub enum ParachuteAction {
1881 #[doc = "Disable auto-release of parachute (i.e. release triggered by crash detectors)."]
1882 PARACHUTE_DISABLE = 0,
1883 #[doc = "Enable auto-release of parachute."]
1884 PARACHUTE_ENABLE = 1,
1885 #[doc = "Release parachute and kill motors."]
1886 PARACHUTE_RELEASE = 2,
1887}
1888impl ParachuteAction {
1889 pub const DEFAULT: Self = Self::PARACHUTE_DISABLE;
1890}
1891impl Default for ParachuteAction {
1892 fn default() -> Self {
1893 Self::DEFAULT
1894 }
1895}
1896bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags for the global position report."] pub struct UtmDataAvailFlags : u8 { # [doc = "The field time contains valid data."] const UTM_DATA_AVAIL_FLAGS_TIME_VALID = 1 ; # [doc = "The field uas_id contains valid data."] const UTM_DATA_AVAIL_FLAGS_UAS_ID_AVAILABLE = 2 ; # [doc = "The fields lat, lon and h_acc contain valid data."] const UTM_DATA_AVAIL_FLAGS_POSITION_AVAILABLE = 4 ; # [doc = "The fields alt and v_acc contain valid data."] const UTM_DATA_AVAIL_FLAGS_ALTITUDE_AVAILABLE = 8 ; # [doc = "The field relative_alt contains valid data."] const UTM_DATA_AVAIL_FLAGS_RELATIVE_ALTITUDE_AVAILABLE = 16 ; # [doc = "The fields vx and vy contain valid data."] const UTM_DATA_AVAIL_FLAGS_HORIZONTAL_VELO_AVAILABLE = 32 ; # [doc = "The field vz contains valid data."] const UTM_DATA_AVAIL_FLAGS_VERTICAL_VELO_AVAILABLE = 64 ; # [doc = "The fields next_lat, next_lon and next_alt contain valid data."] const UTM_DATA_AVAIL_FLAGS_NEXT_WAYPOINT_AVAILABLE = 128 ; } }
1897impl UtmDataAvailFlags {
1898 pub const DEFAULT: Self = Self::UTM_DATA_AVAIL_FLAGS_TIME_VALID;
1899}
1900impl Default for UtmDataAvailFlags {
1901 fn default() -> Self {
1902 Self::DEFAULT
1903 }
1904}
1905bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Bitmap to indicate which dimensions should be ignored by the vehicle: a value of 0b00000000 indicates that none of the setpoint dimensions should be ignored."] pub struct AttitudeTargetTypemask : u8 { # [doc = "Ignore body roll rate"] const ATTITUDE_TARGET_TYPEMASK_BODY_ROLL_RATE_IGNORE = 1 ; # [doc = "Ignore body pitch rate"] const ATTITUDE_TARGET_TYPEMASK_BODY_PITCH_RATE_IGNORE = 2 ; # [doc = "Ignore body yaw rate"] const ATTITUDE_TARGET_TYPEMASK_BODY_YAW_RATE_IGNORE = 4 ; # [doc = "Use 3D body thrust setpoint instead of throttle"] const ATTITUDE_TARGET_TYPEMASK_THRUST_BODY_SET = 32 ; # [doc = "Ignore throttle"] const ATTITUDE_TARGET_TYPEMASK_THROTTLE_IGNORE = 64 ; # [doc = "Ignore attitude"] const ATTITUDE_TARGET_TYPEMASK_ATTITUDE_IGNORE = 128 ; } }
1906impl AttitudeTargetTypemask {
1907 pub const DEFAULT: Self = Self::ATTITUDE_TARGET_TYPEMASK_BODY_ROLL_RATE_IGNORE;
1908}
1909impl Default for AttitudeTargetTypemask {
1910 fn default() -> Self {
1911 Self::DEFAULT
1912 }
1913}
1914#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1915#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1916#[cfg_attr(feature = "serde", serde(tag = "type"))]
1917#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1918#[repr(u32)]
1919pub enum CanFilterOp {
1920 CAN_FILTER_REPLACE = 0,
1921 CAN_FILTER_ADD = 1,
1922 CAN_FILTER_REMOVE = 2,
1923}
1924impl CanFilterOp {
1925 pub const DEFAULT: Self = Self::CAN_FILTER_REPLACE;
1926}
1927impl Default for CanFilterOp {
1928 fn default() -> Self {
1929 Self::DEFAULT
1930 }
1931}
1932#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1933#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1934#[cfg_attr(feature = "serde", serde(tag = "type"))]
1935#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1936#[repr(u32)]
1937#[doc = "Specifies the datatype of a MAVLink extended parameter."]
1938pub enum MavParamExtType {
1939 #[doc = "8-bit unsigned integer"]
1940 MAV_PARAM_EXT_TYPE_UINT8 = 1,
1941 #[doc = "8-bit signed integer"]
1942 MAV_PARAM_EXT_TYPE_INT8 = 2,
1943 #[doc = "16-bit unsigned integer"]
1944 MAV_PARAM_EXT_TYPE_UINT16 = 3,
1945 #[doc = "16-bit signed integer"]
1946 MAV_PARAM_EXT_TYPE_INT16 = 4,
1947 #[doc = "32-bit unsigned integer"]
1948 MAV_PARAM_EXT_TYPE_UINT32 = 5,
1949 #[doc = "32-bit signed integer"]
1950 MAV_PARAM_EXT_TYPE_INT32 = 6,
1951 #[doc = "64-bit unsigned integer"]
1952 MAV_PARAM_EXT_TYPE_UINT64 = 7,
1953 #[doc = "64-bit signed integer"]
1954 MAV_PARAM_EXT_TYPE_INT64 = 8,
1955 #[doc = "32-bit floating-point"]
1956 MAV_PARAM_EXT_TYPE_REAL32 = 9,
1957 #[doc = "64-bit floating-point"]
1958 MAV_PARAM_EXT_TYPE_REAL64 = 10,
1959 #[doc = "Custom Type"]
1960 MAV_PARAM_EXT_TYPE_CUSTOM = 11,
1961}
1962impl MavParamExtType {
1963 pub const DEFAULT: Self = Self::MAV_PARAM_EXT_TYPE_UINT8;
1964}
1965impl Default for MavParamExtType {
1966 fn default() -> Self {
1967 Self::DEFAULT
1968 }
1969}
1970#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1971#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1972#[cfg_attr(feature = "serde", serde(tag = "type"))]
1973#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1974#[repr(u32)]
1975#[doc = "Enumeration of possible mount operation modes. This message is used by obsolete/deprecated gimbal messages."]
1976pub enum MavMountMode {
1977 #[doc = "Load and keep safe position (Roll,Pitch,Yaw) from permanent memory and stop stabilization"]
1978 MAV_MOUNT_MODE_RETRACT = 0,
1979 #[doc = "Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory."]
1980 MAV_MOUNT_MODE_NEUTRAL = 1,
1981 #[doc = "Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization"]
1982 MAV_MOUNT_MODE_MAVLINK_TARGETING = 2,
1983 #[doc = "Load neutral position and start RC Roll,Pitch,Yaw control with stabilization"]
1984 MAV_MOUNT_MODE_RC_TARGETING = 3,
1985 #[doc = "Load neutral position and start to point to Lat,Lon,Alt"]
1986 MAV_MOUNT_MODE_GPS_POINT = 4,
1987 #[doc = "Gimbal tracks system with specified system ID"]
1988 MAV_MOUNT_MODE_SYSID_TARGET = 5,
1989 #[doc = "Gimbal tracks home position"]
1990 MAV_MOUNT_MODE_HOME_LOCATION = 6,
1991}
1992impl MavMountMode {
1993 pub const DEFAULT: Self = Self::MAV_MOUNT_MODE_RETRACT;
1994}
1995impl Default for MavMountMode {
1996 fn default() -> Self {
1997 Self::DEFAULT
1998 }
1999}
2000#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2001#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2002#[cfg_attr(feature = "serde", serde(tag = "type"))]
2003#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2004#[repr(u32)]
2005#[doc = "The ROI (region of interest) for the vehicle. This can be be used by the vehicle for camera/vehicle attitude alignment (see MAV_CMD_NAV_ROI)."]
2006pub enum MavRoi {
2007 #[doc = "No region of interest."]
2008 MAV_ROI_NONE = 0,
2009 #[doc = "Point toward next waypoint, with optional pitch/roll/yaw offset."]
2010 MAV_ROI_WPNEXT = 1,
2011 #[doc = "Point toward given waypoint."]
2012 MAV_ROI_WPINDEX = 2,
2013 #[doc = "Point toward fixed location."]
2014 MAV_ROI_LOCATION = 3,
2015 #[doc = "Point toward of given id."]
2016 MAV_ROI_TARGET = 4,
2017}
2018impl MavRoi {
2019 pub const DEFAULT: Self = Self::MAV_ROI_NONE;
2020}
2021impl Default for MavRoi {
2022 fn default() -> Self {
2023 Self::DEFAULT
2024 }
2025}
2026#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2027#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2028#[cfg_attr(feature = "serde", serde(tag = "type"))]
2029#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2030#[repr(u32)]
2031#[doc = "Modes of illuminator"]
2032pub enum IlluminatorMode {
2033 #[doc = "Illuminator mode is not specified/unknown"]
2034 ILLUMINATOR_MODE_UNKNOWN = 0,
2035 #[doc = "Illuminator behavior is controlled by MAV_CMD_DO_ILLUMINATOR_CONFIGURE settings"]
2036 ILLUMINATOR_MODE_INTERNAL_CONTROL = 1,
2037 #[doc = "Illuminator behavior is controlled by external factors: e.g. an external hardware signal"]
2038 ILLUMINATOR_MODE_EXTERNAL_SYNC = 2,
2039}
2040impl IlluminatorMode {
2041 pub const DEFAULT: Self = Self::ILLUMINATOR_MODE_UNKNOWN;
2042}
2043impl Default for IlluminatorMode {
2044 fn default() -> Self {
2045 Self::DEFAULT
2046 }
2047}
2048#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2049#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2050#[cfg_attr(feature = "serde", serde(tag = "type"))]
2051#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2052#[repr(u32)]
2053#[doc = "Defines how throttle value is represented in MAV_CMD_DO_MOTOR_TEST."]
2054pub enum MotorTestThrottleType {
2055 #[doc = "Throttle as a percentage (0 ~ 100)"]
2056 MOTOR_TEST_THROTTLE_PERCENT = 0,
2057 #[doc = "Throttle as an absolute PWM value (normally in range of 1000~2000)."]
2058 MOTOR_TEST_THROTTLE_PWM = 1,
2059 #[doc = "Throttle pass-through from pilot's transmitter."]
2060 MOTOR_TEST_THROTTLE_PILOT = 2,
2061 #[doc = "Per-motor compass calibration test."]
2062 MOTOR_TEST_COMPASS_CAL = 3,
2063}
2064impl MotorTestThrottleType {
2065 pub const DEFAULT: Self = Self::MOTOR_TEST_THROTTLE_PERCENT;
2066}
2067impl Default for MotorTestThrottleType {
2068 fn default() -> Self {
2069 Self::DEFAULT
2070 }
2071}
2072#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2073#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2074#[cfg_attr(feature = "serde", serde(tag = "type"))]
2075#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2076#[repr(u32)]
2077#[doc = "Camera sources for MAV_CMD_SET_CAMERA_SOURCE"]
2078pub enum CameraSource {
2079 #[doc = "Default camera source."]
2080 CAMERA_SOURCE_DEFAULT = 0,
2081 #[doc = "RGB camera source."]
2082 CAMERA_SOURCE_RGB = 1,
2083 #[doc = "IR camera source."]
2084 CAMERA_SOURCE_IR = 2,
2085 #[doc = "NDVI camera source."]
2086 CAMERA_SOURCE_NDVI = 3,
2087}
2088impl CameraSource {
2089 pub const DEFAULT: Self = Self::CAMERA_SOURCE_DEFAULT;
2090}
2091impl Default for CameraSource {
2092 fn default() -> Self {
2093 Self::DEFAULT
2094 }
2095}
2096#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2097#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2098#[cfg_attr(feature = "serde", serde(tag = "type"))]
2099#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2100#[repr(u32)]
2101#[doc = "Component ids (values) for the different types and instances of onboard hardware/software that might make up a MAVLink system (autopilot, cameras, servos, GPS systems, avoidance systems etc.). Components must use the appropriate ID in their source address when sending messages. Components can also use IDs to determine if they are the intended recipient of an incoming message. The MAV_COMP_ID_ALL value is used to indicate messages that must be processed by all components. When creating new entries, components that can have multiple instances (e.g. cameras, servos etc.) should be allocated sequential values. An appropriate number of values should be left free after these components to allow the number of instances to be expanded."]
2102pub enum MavComponent {
2103 #[doc = "Target id (target_component) used to broadcast messages to all components of the receiving system. Components should attempt to process messages with this component ID and forward to components on any other interfaces. Note: This is not a valid *source* component id for a message."]
2104 MAV_COMP_ID_ALL = 0,
2105 #[doc = "System flight controller component (\"autopilot\"). Only one autopilot is expected in a particular system."]
2106 MAV_COMP_ID_AUTOPILOT1 = 1,
2107 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2108 MAV_COMP_ID_USER1 = 25,
2109 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2110 MAV_COMP_ID_USER2 = 26,
2111 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2112 MAV_COMP_ID_USER3 = 27,
2113 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2114 MAV_COMP_ID_USER4 = 28,
2115 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2116 MAV_COMP_ID_USER5 = 29,
2117 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2118 MAV_COMP_ID_USER6 = 30,
2119 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2120 MAV_COMP_ID_USER7 = 31,
2121 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2122 MAV_COMP_ID_USER8 = 32,
2123 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2124 MAV_COMP_ID_USER9 = 33,
2125 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2126 MAV_COMP_ID_USER10 = 34,
2127 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2128 MAV_COMP_ID_USER11 = 35,
2129 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2130 MAV_COMP_ID_USER12 = 36,
2131 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2132 MAV_COMP_ID_USER13 = 37,
2133 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2134 MAV_COMP_ID_USER14 = 38,
2135 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2136 MAV_COMP_ID_USER15 = 39,
2137 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2138 MAV_COMP_ID_USER16 = 40,
2139 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2140 MAV_COMP_ID_USER17 = 41,
2141 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2142 MAV_COMP_ID_USER18 = 42,
2143 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2144 MAV_COMP_ID_USER19 = 43,
2145 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2146 MAV_COMP_ID_USER20 = 44,
2147 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2148 MAV_COMP_ID_USER21 = 45,
2149 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2150 MAV_COMP_ID_USER22 = 46,
2151 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2152 MAV_COMP_ID_USER23 = 47,
2153 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2154 MAV_COMP_ID_USER24 = 48,
2155 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2156 MAV_COMP_ID_USER25 = 49,
2157 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2158 MAV_COMP_ID_USER26 = 50,
2159 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2160 MAV_COMP_ID_USER27 = 51,
2161 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2162 MAV_COMP_ID_USER28 = 52,
2163 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2164 MAV_COMP_ID_USER29 = 53,
2165 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2166 MAV_COMP_ID_USER30 = 54,
2167 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2168 MAV_COMP_ID_USER31 = 55,
2169 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2170 MAV_COMP_ID_USER32 = 56,
2171 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2172 MAV_COMP_ID_USER33 = 57,
2173 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2174 MAV_COMP_ID_USER34 = 58,
2175 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2176 MAV_COMP_ID_USER35 = 59,
2177 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2178 MAV_COMP_ID_USER36 = 60,
2179 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2180 MAV_COMP_ID_USER37 = 61,
2181 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2182 MAV_COMP_ID_USER38 = 62,
2183 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2184 MAV_COMP_ID_USER39 = 63,
2185 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2186 MAV_COMP_ID_USER40 = 64,
2187 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2188 MAV_COMP_ID_USER41 = 65,
2189 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2190 MAV_COMP_ID_USER42 = 66,
2191 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2192 MAV_COMP_ID_USER43 = 67,
2193 #[doc = "Telemetry radio (e.g. SiK radio, or other component that emits RADIO_STATUS messages)."]
2194 MAV_COMP_ID_TELEMETRY_RADIO = 68,
2195 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2196 MAV_COMP_ID_USER45 = 69,
2197 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2198 MAV_COMP_ID_USER46 = 70,
2199 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2200 MAV_COMP_ID_USER47 = 71,
2201 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2202 MAV_COMP_ID_USER48 = 72,
2203 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2204 MAV_COMP_ID_USER49 = 73,
2205 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2206 MAV_COMP_ID_USER50 = 74,
2207 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2208 MAV_COMP_ID_USER51 = 75,
2209 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2210 MAV_COMP_ID_USER52 = 76,
2211 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2212 MAV_COMP_ID_USER53 = 77,
2213 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2214 MAV_COMP_ID_USER54 = 78,
2215 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2216 MAV_COMP_ID_USER55 = 79,
2217 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2218 MAV_COMP_ID_USER56 = 80,
2219 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2220 MAV_COMP_ID_USER57 = 81,
2221 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2222 MAV_COMP_ID_USER58 = 82,
2223 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2224 MAV_COMP_ID_USER59 = 83,
2225 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2226 MAV_COMP_ID_USER60 = 84,
2227 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2228 MAV_COMP_ID_USER61 = 85,
2229 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2230 MAV_COMP_ID_USER62 = 86,
2231 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2232 MAV_COMP_ID_USER63 = 87,
2233 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2234 MAV_COMP_ID_USER64 = 88,
2235 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2236 MAV_COMP_ID_USER65 = 89,
2237 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2238 MAV_COMP_ID_USER66 = 90,
2239 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2240 MAV_COMP_ID_USER67 = 91,
2241 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2242 MAV_COMP_ID_USER68 = 92,
2243 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2244 MAV_COMP_ID_USER69 = 93,
2245 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2246 MAV_COMP_ID_USER70 = 94,
2247 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2248 MAV_COMP_ID_USER71 = 95,
2249 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2250 MAV_COMP_ID_USER72 = 96,
2251 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2252 MAV_COMP_ID_USER73 = 97,
2253 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2254 MAV_COMP_ID_USER74 = 98,
2255 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
2256 MAV_COMP_ID_USER75 = 99,
2257 #[doc = "Camera #1."]
2258 MAV_COMP_ID_CAMERA = 100,
2259 #[doc = "Camera #2."]
2260 MAV_COMP_ID_CAMERA2 = 101,
2261 #[doc = "Camera #3."]
2262 MAV_COMP_ID_CAMERA3 = 102,
2263 #[doc = "Camera #4."]
2264 MAV_COMP_ID_CAMERA4 = 103,
2265 #[doc = "Camera #5."]
2266 MAV_COMP_ID_CAMERA5 = 104,
2267 #[doc = "Camera #6."]
2268 MAV_COMP_ID_CAMERA6 = 105,
2269 #[doc = "Servo #1."]
2270 MAV_COMP_ID_SERVO1 = 140,
2271 #[doc = "Servo #2."]
2272 MAV_COMP_ID_SERVO2 = 141,
2273 #[doc = "Servo #3."]
2274 MAV_COMP_ID_SERVO3 = 142,
2275 #[doc = "Servo #4."]
2276 MAV_COMP_ID_SERVO4 = 143,
2277 #[doc = "Servo #5."]
2278 MAV_COMP_ID_SERVO5 = 144,
2279 #[doc = "Servo #6."]
2280 MAV_COMP_ID_SERVO6 = 145,
2281 #[doc = "Servo #7."]
2282 MAV_COMP_ID_SERVO7 = 146,
2283 #[doc = "Servo #8."]
2284 MAV_COMP_ID_SERVO8 = 147,
2285 #[doc = "Servo #9."]
2286 MAV_COMP_ID_SERVO9 = 148,
2287 #[doc = "Servo #10."]
2288 MAV_COMP_ID_SERVO10 = 149,
2289 #[doc = "Servo #11."]
2290 MAV_COMP_ID_SERVO11 = 150,
2291 #[doc = "Servo #12."]
2292 MAV_COMP_ID_SERVO12 = 151,
2293 #[doc = "Servo #13."]
2294 MAV_COMP_ID_SERVO13 = 152,
2295 #[doc = "Servo #14."]
2296 MAV_COMP_ID_SERVO14 = 153,
2297 #[doc = "Gimbal #1."]
2298 MAV_COMP_ID_GIMBAL = 154,
2299 #[doc = "Logging component."]
2300 MAV_COMP_ID_LOG = 155,
2301 #[doc = "Automatic Dependent Surveillance-Broadcast (ADS-B) component."]
2302 MAV_COMP_ID_ADSB = 156,
2303 #[doc = "On Screen Display (OSD) devices for video links."]
2304 MAV_COMP_ID_OSD = 157,
2305 #[doc = "Generic autopilot peripheral component ID. Meant for devices that do not implement the parameter microservice."]
2306 MAV_COMP_ID_PERIPHERAL = 158,
2307 #[doc = "Gimbal ID for QX1."]
2308 MAV_COMP_ID_QX1_GIMBAL = 159,
2309 #[doc = "FLARM collision alert component."]
2310 MAV_COMP_ID_FLARM = 160,
2311 #[doc = "Parachute component."]
2312 MAV_COMP_ID_PARACHUTE = 161,
2313 #[doc = "Winch component."]
2314 MAV_COMP_ID_WINCH = 169,
2315 #[doc = "Gimbal #2."]
2316 MAV_COMP_ID_GIMBAL2 = 171,
2317 #[doc = "Gimbal #3."]
2318 MAV_COMP_ID_GIMBAL3 = 172,
2319 #[doc = "Gimbal #4"]
2320 MAV_COMP_ID_GIMBAL4 = 173,
2321 #[doc = "Gimbal #5."]
2322 MAV_COMP_ID_GIMBAL5 = 174,
2323 #[doc = "Gimbal #6."]
2324 MAV_COMP_ID_GIMBAL6 = 175,
2325 #[doc = "Battery #1."]
2326 MAV_COMP_ID_BATTERY = 180,
2327 #[doc = "Battery #2."]
2328 MAV_COMP_ID_BATTERY2 = 181,
2329 #[doc = "CAN over MAVLink client."]
2330 MAV_COMP_ID_MAVCAN = 189,
2331 #[doc = "Component that can generate/supply a mission flight plan (e.g. GCS or developer API)."]
2332 MAV_COMP_ID_MISSIONPLANNER = 190,
2333 #[doc = "Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on."]
2334 MAV_COMP_ID_ONBOARD_COMPUTER = 191,
2335 #[doc = "Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on."]
2336 MAV_COMP_ID_ONBOARD_COMPUTER2 = 192,
2337 #[doc = "Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on."]
2338 MAV_COMP_ID_ONBOARD_COMPUTER3 = 193,
2339 #[doc = "Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on."]
2340 MAV_COMP_ID_ONBOARD_COMPUTER4 = 194,
2341 #[doc = "Component that finds an optimal path between points based on a certain constraint (e.g. minimum snap, shortest path, cost, etc.)."]
2342 MAV_COMP_ID_PATHPLANNER = 195,
2343 #[doc = "Component that plans a collision free path between two points."]
2344 MAV_COMP_ID_OBSTACLE_AVOIDANCE = 196,
2345 #[doc = "Component that provides position estimates using VIO techniques."]
2346 MAV_COMP_ID_VISUAL_INERTIAL_ODOMETRY = 197,
2347 #[doc = "Component that manages pairing of vehicle and GCS."]
2348 MAV_COMP_ID_PAIRING_MANAGER = 198,
2349 #[doc = "Inertial Measurement Unit (IMU) #1."]
2350 MAV_COMP_ID_IMU = 200,
2351 #[doc = "Inertial Measurement Unit (IMU) #2."]
2352 MAV_COMP_ID_IMU_2 = 201,
2353 #[doc = "Inertial Measurement Unit (IMU) #3."]
2354 MAV_COMP_ID_IMU_3 = 202,
2355 #[doc = "GPS #1."]
2356 MAV_COMP_ID_GPS = 220,
2357 #[doc = "GPS #2."]
2358 MAV_COMP_ID_GPS2 = 221,
2359 #[doc = "Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet)."]
2360 MAV_COMP_ID_ODID_TXRX_1 = 236,
2361 #[doc = "Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet)."]
2362 MAV_COMP_ID_ODID_TXRX_2 = 237,
2363 #[doc = "Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet)."]
2364 MAV_COMP_ID_ODID_TXRX_3 = 238,
2365 #[doc = "Component to bridge MAVLink to UDP (i.e. from a UART)."]
2366 MAV_COMP_ID_UDP_BRIDGE = 240,
2367 #[doc = "Component to bridge to UART (i.e. from UDP)."]
2368 MAV_COMP_ID_UART_BRIDGE = 241,
2369 #[doc = "Component handling TUNNEL messages (e.g. vendor specific GUI of a component)."]
2370 MAV_COMP_ID_TUNNEL_NODE = 242,
2371 #[doc = "Illuminator"]
2372 MAV_COMP_ID_ILLUMINATOR = 243,
2373 #[doc = "Deprecated, don't use. Component for handling system messages (e.g. to ARM, takeoff, etc.)."]
2374 MAV_COMP_ID_SYSTEM_CONTROL = 250,
2375}
2376impl MavComponent {
2377 pub const DEFAULT: Self = Self::MAV_COMP_ID_ALL;
2378}
2379impl Default for MavComponent {
2380 fn default() -> Self {
2381 Self::DEFAULT
2382 }
2383}
2384#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2385#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2386#[cfg_attr(feature = "serde", serde(tag = "type"))]
2387#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2388#[repr(u32)]
2389#[doc = "Result of mission operation (in a MISSION_ACK message)."]
2390pub enum MavMissionResult {
2391 #[doc = "mission accepted OK"]
2392 MAV_MISSION_ACCEPTED = 0,
2393 #[doc = "Generic error / not accepting mission commands at all right now."]
2394 MAV_MISSION_ERROR = 1,
2395 #[doc = "Coordinate frame is not supported."]
2396 MAV_MISSION_UNSUPPORTED_FRAME = 2,
2397 #[doc = "Command is not supported."]
2398 MAV_MISSION_UNSUPPORTED = 3,
2399 #[doc = "Mission items exceed storage space."]
2400 MAV_MISSION_NO_SPACE = 4,
2401 #[doc = "One of the parameters has an invalid value."]
2402 MAV_MISSION_INVALID = 5,
2403 #[doc = "param1 has an invalid value."]
2404 MAV_MISSION_INVALID_PARAM1 = 6,
2405 #[doc = "param2 has an invalid value."]
2406 MAV_MISSION_INVALID_PARAM2 = 7,
2407 #[doc = "param3 has an invalid value."]
2408 MAV_MISSION_INVALID_PARAM3 = 8,
2409 #[doc = "param4 has an invalid value."]
2410 MAV_MISSION_INVALID_PARAM4 = 9,
2411 #[doc = "x / param5 has an invalid value."]
2412 MAV_MISSION_INVALID_PARAM5_X = 10,
2413 #[doc = "y / param6 has an invalid value."]
2414 MAV_MISSION_INVALID_PARAM6_Y = 11,
2415 #[doc = "z / param7 has an invalid value."]
2416 MAV_MISSION_INVALID_PARAM7 = 12,
2417 #[doc = "Mission item received out of sequence"]
2418 MAV_MISSION_INVALID_SEQUENCE = 13,
2419 #[doc = "Not accepting any mission commands from this communication partner."]
2420 MAV_MISSION_DENIED = 14,
2421 #[doc = "Current mission operation cancelled (e.g. mission upload, mission download)."]
2422 MAV_MISSION_OPERATION_CANCELLED = 15,
2423}
2424impl MavMissionResult {
2425 pub const DEFAULT: Self = Self::MAV_MISSION_ACCEPTED;
2426}
2427impl Default for MavMissionResult {
2428 fn default() -> Self {
2429 Self::DEFAULT
2430 }
2431}
2432bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Gimbal device (low level) capability flags (bitmap)."] pub struct GimbalDeviceCapFlags : u16 { # [doc = "Gimbal device supports a retracted position."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT = 1 ; # [doc = "Gimbal device supports a horizontal, forward looking position, stabilized."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL = 2 ; # [doc = "Gimbal device supports rotating around roll axis."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS = 4 ; # [doc = "Gimbal device supports to follow a roll angle relative to the vehicle."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW = 8 ; # [doc = "Gimbal device supports locking to a roll angle (generally that's the default with roll stabilized)."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK = 16 ; # [doc = "Gimbal device supports rotating around pitch axis."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS = 32 ; # [doc = "Gimbal device supports to follow a pitch angle relative to the vehicle."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW = 64 ; # [doc = "Gimbal device supports locking to a pitch angle (generally that's the default with pitch stabilized)."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK = 128 ; # [doc = "Gimbal device supports rotating around yaw axis."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS = 256 ; # [doc = "Gimbal device supports to follow a yaw angle relative to the vehicle (generally that's the default)."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW = 512 ; # [doc = "Gimbal device supports locking to an absolute heading, i.e., yaw angle relative to North (earth frame, often this is an option available)."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK = 1024 ; # [doc = "Gimbal device supports yawing/panning infinitely (e.g. using slip disk)."] const GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAW = 2048 ; # [doc = "Gimbal device supports yaw angles and angular velocities relative to North (earth frame). This usually requires support by an autopilot via AUTOPILOT_STATE_FOR_GIMBAL_DEVICE. Support can go on and off during runtime, which is reported by the flag GIMBAL_DEVICE_FLAGS_CAN_ACCEPT_YAW_IN_EARTH_FRAME."] const GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_YAW_IN_EARTH_FRAME = 4096 ; # [doc = "Gimbal device supports radio control inputs as an alternative input for controlling the gimbal orientation."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_RC_INPUTS = 8192 ; } }
2433impl GimbalDeviceCapFlags {
2434 pub const DEFAULT: Self = Self::GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT;
2435}
2436impl Default for GimbalDeviceCapFlags {
2437 fn default() -> Self {
2438 Self::DEFAULT
2439 }
2440}
2441bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "These flags encode the MAV mode."] pub struct MavModeFlag : u8 { # [doc = "0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. Additional note: this flag is to be ignore when sent in the command MAV_CMD_DO_SET_MODE and MAV_CMD_COMPONENT_ARM_DISARM shall be used instead. The flag can still be used to report the armed state."] const MAV_MODE_FLAG_SAFETY_ARMED = 128 ; # [doc = "0b01000000 remote control input is enabled."] const MAV_MODE_FLAG_MANUAL_INPUT_ENABLED = 64 ; # [doc = "0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational."] const MAV_MODE_FLAG_HIL_ENABLED = 32 ; # [doc = "0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around."] const MAV_MODE_FLAG_STABILIZE_ENABLED = 16 ; # [doc = "0b00001000 guided mode enabled, system flies waypoints / mission items."] const MAV_MODE_FLAG_GUIDED_ENABLED = 8 ; # [doc = "0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation."] const MAV_MODE_FLAG_AUTO_ENABLED = 4 ; # [doc = "0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations."] const MAV_MODE_FLAG_TEST_ENABLED = 2 ; # [doc = "0b00000001 Reserved for future use."] const MAV_MODE_FLAG_CUSTOM_MODE_ENABLED = 1 ; } }
2442impl MavModeFlag {
2443 pub const DEFAULT: Self = Self::MAV_MODE_FLAG_SAFETY_ARMED;
2444}
2445impl Default for MavModeFlag {
2446 fn default() -> Self {
2447 Self::DEFAULT
2448 }
2449}
2450#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2451#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2452#[cfg_attr(feature = "serde", serde(tag = "type"))]
2453#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2454#[repr(u32)]
2455#[doc = "Axes that will be autotuned by MAV_CMD_DO_AUTOTUNE_ENABLE. Note that at least one flag must be set in MAV_CMD_DO_AUTOTUNE_ENABLE.param2: if none are set, the flight stack will tune its default set of axes."]
2456pub enum AutotuneAxis {
2457 #[doc = "Autotune roll axis."]
2458 AUTOTUNE_AXIS_ROLL = 1,
2459 #[doc = "Autotune pitch axis."]
2460 AUTOTUNE_AXIS_PITCH = 2,
2461 #[doc = "Autotune yaw axis."]
2462 AUTOTUNE_AXIS_YAW = 4,
2463}
2464impl AutotuneAxis {
2465 pub const DEFAULT: Self = Self::AUTOTUNE_AXIS_ROLL;
2466}
2467impl Default for AutotuneAxis {
2468 fn default() -> Self {
2469 Self::DEFAULT
2470 }
2471}
2472#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2473#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2474#[cfg_attr(feature = "serde", serde(tag = "type"))]
2475#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2476#[repr(u32)]
2477#[doc = "Generalized UAVCAN node mode"]
2478pub enum UavcanNodeMode {
2479 #[doc = "The node is performing its primary functions."]
2480 UAVCAN_NODE_MODE_OPERATIONAL = 0,
2481 #[doc = "The node is initializing; this mode is entered immediately after startup."]
2482 UAVCAN_NODE_MODE_INITIALIZATION = 1,
2483 #[doc = "The node is under maintenance."]
2484 UAVCAN_NODE_MODE_MAINTENANCE = 2,
2485 #[doc = "The node is in the process of updating its software."]
2486 UAVCAN_NODE_MODE_SOFTWARE_UPDATE = 3,
2487 #[doc = "The node is no longer available online."]
2488 UAVCAN_NODE_MODE_OFFLINE = 7,
2489}
2490impl UavcanNodeMode {
2491 pub const DEFAULT: Self = Self::UAVCAN_NODE_MODE_OPERATIONAL;
2492}
2493impl Default for UavcanNodeMode {
2494 fn default() -> Self {
2495 Self::DEFAULT
2496 }
2497}
2498#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2499#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2500#[cfg_attr(feature = "serde", serde(tag = "type"))]
2501#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2502#[repr(u32)]
2503#[doc = "Flags for CURRENT_EVENT_SEQUENCE."]
2504pub enum MavEventCurrentSequenceFlags {
2505 #[doc = "A sequence reset has happened (e.g. vehicle reboot)."]
2506 MAV_EVENT_CURRENT_SEQUENCE_FLAGS_RESET = 1,
2507}
2508impl MavEventCurrentSequenceFlags {
2509 pub const DEFAULT: Self = Self::MAV_EVENT_CURRENT_SEQUENCE_FLAGS_RESET;
2510}
2511impl Default for MavEventCurrentSequenceFlags {
2512 fn default() -> Self {
2513 Self::DEFAULT
2514 }
2515}
2516#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2517#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2518#[cfg_attr(feature = "serde", serde(tag = "type"))]
2519#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2520#[repr(u32)]
2521#[doc = "Battery mode. Note, the normal operation mode (i.e. when flying) should be reported as MAV_BATTERY_MODE_UNKNOWN to allow message trimming in normal flight."]
2522pub enum MavBatteryMode {
2523 #[doc = "Battery mode not supported/unknown battery mode/normal operation."]
2524 MAV_BATTERY_MODE_UNKNOWN = 0,
2525 #[doc = "Battery is auto discharging (towards storage level)."]
2526 MAV_BATTERY_MODE_AUTO_DISCHARGING = 1,
2527 #[doc = "Battery in hot-swap mode (current limited to prevent spikes that might damage sensitive electrical circuits)."]
2528 MAV_BATTERY_MODE_HOT_SWAP = 2,
2529}
2530impl MavBatteryMode {
2531 pub const DEFAULT: Self = Self::MAV_BATTERY_MODE_UNKNOWN;
2532}
2533impl Default for MavBatteryMode {
2534 fn default() -> Self {
2535 Self::DEFAULT
2536 }
2537}
2538#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2539#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2540#[cfg_attr(feature = "serde", serde(tag = "type"))]
2541#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2542#[repr(u32)]
2543#[doc = "Bitmap of options for the MAV_CMD_DO_REPOSITION"]
2544pub enum MavDoRepositionFlags {
2545 #[doc = "The aircraft should immediately transition into guided. This should not be set for follow me applications"]
2546 MAV_DO_REPOSITION_FLAGS_CHANGE_MODE = 1,
2547}
2548impl MavDoRepositionFlags {
2549 pub const DEFAULT: Self = Self::MAV_DO_REPOSITION_FLAGS_CHANGE_MODE;
2550}
2551impl Default for MavDoRepositionFlags {
2552 fn default() -> Self {
2553 Self::DEFAULT
2554 }
2555}
2556#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2557#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2558#[cfg_attr(feature = "serde", serde(tag = "type"))]
2559#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2560#[repr(u32)]
2561#[doc = "Aircraft-rated danger from this threat."]
2562pub enum MavCollisionThreatLevel {
2563 #[doc = "Not a threat"]
2564 MAV_COLLISION_THREAT_LEVEL_NONE = 0,
2565 #[doc = "Craft is mildly concerned about this threat"]
2566 MAV_COLLISION_THREAT_LEVEL_LOW = 1,
2567 #[doc = "Craft is panicking, and may take actions to avoid threat"]
2568 MAV_COLLISION_THREAT_LEVEL_HIGH = 2,
2569}
2570impl MavCollisionThreatLevel {
2571 pub const DEFAULT: Self = Self::MAV_COLLISION_THREAT_LEVEL_NONE;
2572}
2573impl Default for MavCollisionThreatLevel {
2574 fn default() -> Self {
2575 Self::DEFAULT
2576 }
2577}
2578#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2579#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2580#[cfg_attr(feature = "serde", serde(tag = "type"))]
2581#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2582#[repr(u32)]
2583#[doc = "Type of landing target"]
2584pub enum LandingTargetType {
2585 #[doc = "Landing target signaled by light beacon (ex: IR-LOCK)"]
2586 LANDING_TARGET_TYPE_LIGHT_BEACON = 0,
2587 #[doc = "Landing target signaled by radio beacon (ex: ILS, NDB)"]
2588 LANDING_TARGET_TYPE_RADIO_BEACON = 1,
2589 #[doc = "Landing target represented by a fiducial marker (ex: ARTag)"]
2590 LANDING_TARGET_TYPE_VISION_FIDUCIAL = 2,
2591 #[doc = "Landing target represented by a pre-defined visual shape/feature (ex: X-marker, H-marker, square)"]
2592 LANDING_TARGET_TYPE_VISION_OTHER = 3,
2593}
2594impl LandingTargetType {
2595 pub const DEFAULT: Self = Self::LANDING_TARGET_TYPE_LIGHT_BEACON;
2596}
2597impl Default for LandingTargetType {
2598 fn default() -> Self {
2599 Self::DEFAULT
2600 }
2601}
2602#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2603#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2604#[cfg_attr(feature = "serde", serde(tag = "type"))]
2605#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2606#[repr(u32)]
2607#[doc = "MAVLINK component type reported in HEARTBEAT message. Flight controllers must report the type of the vehicle on which they are mounted (e.g. MAV_TYPE_OCTOROTOR). All other components must report a value appropriate for their type (e.g. a camera must use MAV_TYPE_CAMERA)."]
2608pub enum MavType {
2609 #[doc = "Generic micro air vehicle"]
2610 MAV_TYPE_GENERIC = 0,
2611 #[doc = "Fixed wing aircraft."]
2612 MAV_TYPE_FIXED_WING = 1,
2613 #[doc = "Quadrotor"]
2614 MAV_TYPE_QUADROTOR = 2,
2615 #[doc = "Coaxial helicopter"]
2616 MAV_TYPE_COAXIAL = 3,
2617 #[doc = "Normal helicopter with tail rotor."]
2618 MAV_TYPE_HELICOPTER = 4,
2619 #[doc = "Ground installation"]
2620 MAV_TYPE_ANTENNA_TRACKER = 5,
2621 #[doc = "Operator control unit / ground control station"]
2622 MAV_TYPE_GCS = 6,
2623 #[doc = "Airship, controlled"]
2624 MAV_TYPE_AIRSHIP = 7,
2625 #[doc = "Free balloon, uncontrolled"]
2626 MAV_TYPE_FREE_BALLOON = 8,
2627 #[doc = "Rocket"]
2628 MAV_TYPE_ROCKET = 9,
2629 #[doc = "Ground rover"]
2630 MAV_TYPE_GROUND_ROVER = 10,
2631 #[doc = "Surface vessel, boat, ship"]
2632 MAV_TYPE_SURFACE_BOAT = 11,
2633 #[doc = "Submarine"]
2634 MAV_TYPE_SUBMARINE = 12,
2635 #[doc = "Hexarotor"]
2636 MAV_TYPE_HEXAROTOR = 13,
2637 #[doc = "Octorotor"]
2638 MAV_TYPE_OCTOROTOR = 14,
2639 #[doc = "Tricopter"]
2640 MAV_TYPE_TRICOPTER = 15,
2641 #[doc = "Flapping wing"]
2642 MAV_TYPE_FLAPPING_WING = 16,
2643 #[doc = "Kite"]
2644 MAV_TYPE_KITE = 17,
2645 #[doc = "Onboard companion controller"]
2646 MAV_TYPE_ONBOARD_CONTROLLER = 18,
2647 #[doc = "Two-rotor Tailsitter VTOL that additionally uses control surfaces in vertical operation. Note, value previously named MAV_TYPE_VTOL_DUOROTOR."]
2648 MAV_TYPE_VTOL_TAILSITTER_DUOROTOR = 19,
2649 #[doc = "Quad-rotor Tailsitter VTOL using a V-shaped quad config in vertical operation. Note: value previously named MAV_TYPE_VTOL_QUADROTOR."]
2650 MAV_TYPE_VTOL_TAILSITTER_QUADROTOR = 20,
2651 #[doc = "Tiltrotor VTOL. Fuselage and wings stay (nominally) horizontal in all flight phases. It able to tilt (some) rotors to provide thrust in cruise flight."]
2652 MAV_TYPE_VTOL_TILTROTOR = 21,
2653 #[doc = "VTOL with separate fixed rotors for hover and cruise flight. Fuselage and wings stay (nominally) horizontal in all flight phases."]
2654 MAV_TYPE_VTOL_FIXEDROTOR = 22,
2655 #[doc = "Tailsitter VTOL. Fuselage and wings orientation changes depending on flight phase: vertical for hover, horizontal for cruise. Use more specific VTOL MAV_TYPE_VTOL_TAILSITTER_DUOROTOR or MAV_TYPE_VTOL_TAILSITTER_QUADROTOR if appropriate."]
2656 MAV_TYPE_VTOL_TAILSITTER = 23,
2657 #[doc = "Tiltwing VTOL. Fuselage stays horizontal in all flight phases. The whole wing, along with any attached engine, can tilt between vertical and horizontal mode."]
2658 MAV_TYPE_VTOL_TILTWING = 24,
2659 #[doc = "VTOL reserved 5"]
2660 MAV_TYPE_VTOL_RESERVED5 = 25,
2661 #[doc = "Gimbal"]
2662 MAV_TYPE_GIMBAL = 26,
2663 #[doc = "ADSB system"]
2664 MAV_TYPE_ADSB = 27,
2665 #[doc = "Steerable, nonrigid airfoil"]
2666 MAV_TYPE_PARAFOIL = 28,
2667 #[doc = "Dodecarotor"]
2668 MAV_TYPE_DODECAROTOR = 29,
2669 #[doc = "Camera"]
2670 MAV_TYPE_CAMERA = 30,
2671 #[doc = "Charging station"]
2672 MAV_TYPE_CHARGING_STATION = 31,
2673 #[doc = "FLARM collision avoidance system"]
2674 MAV_TYPE_FLARM = 32,
2675 #[doc = "Servo"]
2676 MAV_TYPE_SERVO = 33,
2677 #[doc = "Open Drone ID. See <https://mavlink.io/en/services/opendroneid.html>."]
2678 MAV_TYPE_ODID = 34,
2679 #[doc = "Decarotor"]
2680 MAV_TYPE_DECAROTOR = 35,
2681 #[doc = "Battery"]
2682 MAV_TYPE_BATTERY = 36,
2683 #[doc = "Parachute"]
2684 MAV_TYPE_PARACHUTE = 37,
2685 #[doc = "Log"]
2686 MAV_TYPE_LOG = 38,
2687 #[doc = "OSD"]
2688 MAV_TYPE_OSD = 39,
2689 #[doc = "IMU"]
2690 MAV_TYPE_IMU = 40,
2691 #[doc = "GPS"]
2692 MAV_TYPE_GPS = 41,
2693 #[doc = "Winch"]
2694 MAV_TYPE_WINCH = 42,
2695 #[doc = "Generic multirotor that does not fit into a specific type or whose type is unknown"]
2696 MAV_TYPE_GENERIC_MULTIROTOR = 43,
2697 #[doc = "Illuminator. An illuminator is a light source that is used for lighting up dark areas external to the sytstem: e.g. a torch or searchlight (as opposed to a light source for illuminating the system itself, e.g. an indicator light)."]
2698 MAV_TYPE_ILLUMINATOR = 44,
2699 #[doc = "Orbiter spacecraft. Includes satellites orbiting terrestrial and extra-terrestrial bodies. Follows NASA Spacecraft Classification."]
2700 MAV_TYPE_SPACECRAFT_ORBITER = 45,
2701}
2702impl MavType {
2703 pub const DEFAULT: Self = Self::MAV_TYPE_GENERIC;
2704}
2705impl Default for MavType {
2706 fn default() -> Self {
2707 Self::DEFAULT
2708 }
2709}
2710bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "These encode the sensors whose status is sent as part of the SYS_STATUS message."] pub struct MavSysStatusSensor : u32 { # [doc = "0x01 3D gyro"] const MAV_SYS_STATUS_SENSOR_3D_GYRO = 1 ; # [doc = "0x02 3D accelerometer"] const MAV_SYS_STATUS_SENSOR_3D_ACCEL = 2 ; # [doc = "0x04 3D magnetometer"] const MAV_SYS_STATUS_SENSOR_3D_MAG = 4 ; # [doc = "0x08 absolute pressure"] const MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE = 8 ; # [doc = "0x10 differential pressure"] const MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE = 16 ; # [doc = "0x20 GPS"] const MAV_SYS_STATUS_SENSOR_GPS = 32 ; # [doc = "0x40 optical flow"] const MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW = 64 ; # [doc = "0x80 computer vision position"] const MAV_SYS_STATUS_SENSOR_VISION_POSITION = 128 ; # [doc = "0x100 laser based position"] const MAV_SYS_STATUS_SENSOR_LASER_POSITION = 256 ; # [doc = "0x200 external ground truth (Vicon or Leica)"] const MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH = 512 ; # [doc = "0x400 3D angular rate control"] const MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL = 1024 ; # [doc = "0x800 attitude stabilization"] const MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION = 2048 ; # [doc = "0x1000 yaw position"] const MAV_SYS_STATUS_SENSOR_YAW_POSITION = 4096 ; # [doc = "0x2000 z/altitude control"] const MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL = 8192 ; # [doc = "0x4000 x/y position control"] const MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL = 16384 ; # [doc = "0x8000 motor outputs / control"] const MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS = 32768 ; # [doc = "0x10000 RC receiver"] const MAV_SYS_STATUS_SENSOR_RC_RECEIVER = 65536 ; # [doc = "0x20000 2nd 3D gyro"] const MAV_SYS_STATUS_SENSOR_3D_GYRO2 = 131072 ; # [doc = "0x40000 2nd 3D accelerometer"] const MAV_SYS_STATUS_SENSOR_3D_ACCEL2 = 262144 ; # [doc = "0x80000 2nd 3D magnetometer"] const MAV_SYS_STATUS_SENSOR_3D_MAG2 = 524288 ; # [doc = "0x100000 geofence"] const MAV_SYS_STATUS_GEOFENCE = 1048576 ; # [doc = "0x200000 AHRS subsystem health"] const MAV_SYS_STATUS_AHRS = 2097152 ; # [doc = "0x400000 Terrain subsystem health"] const MAV_SYS_STATUS_TERRAIN = 4194304 ; # [doc = "0x800000 Motors are reversed"] const MAV_SYS_STATUS_REVERSE_MOTOR = 8388608 ; # [doc = "0x1000000 Logging"] const MAV_SYS_STATUS_LOGGING = 16777216 ; # [doc = "0x2000000 Battery"] const MAV_SYS_STATUS_SENSOR_BATTERY = 33554432 ; # [doc = "0x4000000 Proximity"] const MAV_SYS_STATUS_SENSOR_PROXIMITY = 67108864 ; # [doc = "0x8000000 Satellite Communication"] const MAV_SYS_STATUS_SENSOR_SATCOM = 134217728 ; # [doc = "0x10000000 pre-arm check status. Always healthy when armed"] const MAV_SYS_STATUS_PREARM_CHECK = 268435456 ; # [doc = "0x20000000 Avoidance/collision prevention"] const MAV_SYS_STATUS_OBSTACLE_AVOIDANCE = 536870912 ; # [doc = "0x40000000 propulsion (actuator, esc, motor or propellor)"] const MAV_SYS_STATUS_SENSOR_PROPULSION = 1073741824 ; # [doc = "0x80000000 Extended bit-field are used for further sensor status bits (needs to be set in onboard_control_sensors_present only)"] const MAV_SYS_STATUS_EXTENSION_USED = 2147483648 ; } }
2711impl MavSysStatusSensor {
2712 pub const DEFAULT: Self = Self::MAV_SYS_STATUS_SENSOR_3D_GYRO;
2713}
2714impl Default for MavSysStatusSensor {
2715 fn default() -> Self {
2716 Self::DEFAULT
2717 }
2718}
2719#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2720#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2721#[cfg_attr(feature = "serde", serde(tag = "type"))]
2722#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2723#[repr(u32)]
2724#[doc = "These flags are used to diagnose the failure state of CELLULAR_STATUS"]
2725pub enum CellularNetworkFailedReason {
2726 #[doc = "No error"]
2727 CELLULAR_NETWORK_FAILED_REASON_NONE = 0,
2728 #[doc = "Error state is unknown"]
2729 CELLULAR_NETWORK_FAILED_REASON_UNKNOWN = 1,
2730 #[doc = "SIM is required for the modem but missing"]
2731 CELLULAR_NETWORK_FAILED_REASON_SIM_MISSING = 2,
2732 #[doc = "SIM is available, but not usable for connection"]
2733 CELLULAR_NETWORK_FAILED_REASON_SIM_ERROR = 3,
2734}
2735impl CellularNetworkFailedReason {
2736 pub const DEFAULT: Self = Self::CELLULAR_NETWORK_FAILED_REASON_NONE;
2737}
2738impl Default for CellularNetworkFailedReason {
2739 fn default() -> Self {
2740 Self::DEFAULT
2741 }
2742}
2743bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Illuminator module error flags (bitmap, 0 means no error)"] pub struct IlluminatorErrorFlags : u32 { # [doc = "Illuminator thermal throttling error."] const ILLUMINATOR_ERROR_FLAGS_THERMAL_THROTTLING = 1 ; # [doc = "Illuminator over temperature shutdown error."] const ILLUMINATOR_ERROR_FLAGS_OVER_TEMPERATURE_SHUTDOWN = 2 ; # [doc = "Illuminator thermistor failure."] const ILLUMINATOR_ERROR_FLAGS_THERMISTOR_FAILURE = 4 ; } }
2744impl IlluminatorErrorFlags {
2745 pub const DEFAULT: Self = Self::ILLUMINATOR_ERROR_FLAGS_THERMAL_THROTTLING;
2746}
2747impl Default for IlluminatorErrorFlags {
2748 fn default() -> Self {
2749 Self::DEFAULT
2750 }
2751}
2752#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2753#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2754#[cfg_attr(feature = "serde", serde(tag = "type"))]
2755#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2756#[repr(u32)]
2757#[doc = "A data stream is not a fixed set of messages, but rather a recommendation to the autopilot software. Individual autopilots may or may not obey the recommended messages."]
2758pub enum MavDataStream {
2759 #[doc = "Enable all data streams"]
2760 MAV_DATA_STREAM_ALL = 0,
2761 #[doc = "Enable IMU_RAW, GPS_RAW, GPS_STATUS packets."]
2762 MAV_DATA_STREAM_RAW_SENSORS = 1,
2763 #[doc = "Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS"]
2764 MAV_DATA_STREAM_EXTENDED_STATUS = 2,
2765 #[doc = "Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW"]
2766 MAV_DATA_STREAM_RC_CHANNELS = 3,
2767 #[doc = "Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT."]
2768 MAV_DATA_STREAM_RAW_CONTROLLER = 4,
2769 #[doc = "Enable LOCAL_POSITION, GLOBAL_POSITION_INT messages."]
2770 MAV_DATA_STREAM_POSITION = 6,
2771 #[doc = "Dependent on the autopilot"]
2772 MAV_DATA_STREAM_EXTRA1 = 10,
2773 #[doc = "Dependent on the autopilot"]
2774 MAV_DATA_STREAM_EXTRA2 = 11,
2775 #[doc = "Dependent on the autopilot"]
2776 MAV_DATA_STREAM_EXTRA3 = 12,
2777}
2778impl MavDataStream {
2779 pub const DEFAULT: Self = Self::MAV_DATA_STREAM_ALL;
2780}
2781impl Default for MavDataStream {
2782 fn default() -> Self {
2783 Self::DEFAULT
2784 }
2785}
2786#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2787#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2788#[cfg_attr(feature = "serde", serde(tag = "type"))]
2789#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2790#[repr(u32)]
2791#[doc = "Video stream types"]
2792pub enum VideoStreamType {
2793 #[doc = "Stream is RTSP"]
2794 VIDEO_STREAM_TYPE_RTSP = 0,
2795 #[doc = "Stream is RTP UDP (URI gives the port number)"]
2796 VIDEO_STREAM_TYPE_RTPUDP = 1,
2797 #[doc = "Stream is MPEG on TCP"]
2798 VIDEO_STREAM_TYPE_TCP_MPEG = 2,
2799 #[doc = "Stream is MPEG TS (URI gives the port number)"]
2800 VIDEO_STREAM_TYPE_MPEG_TS = 3,
2801}
2802impl VideoStreamType {
2803 pub const DEFAULT: Self = Self::VIDEO_STREAM_TYPE_RTSP;
2804}
2805impl Default for VideoStreamType {
2806 fn default() -> Self {
2807 Self::DEFAULT
2808 }
2809}
2810#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2811#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2812#[cfg_attr(feature = "serde", serde(tag = "type"))]
2813#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2814#[repr(u32)]
2815#[doc = "Standard modes with a well understood meaning across flight stacks and vehicle types. For example, most flight stack have the concept of a \"return\" or \"RTL\" mode that takes a vehicle to safety, even though the precise mechanics of this mode may differ. The modes supported by a flight stack can be queried using AVAILABLE_MODES and set using MAV_CMD_DO_SET_STANDARD_MODE. The current mode is streamed in CURRENT_MODE. See <https://mavlink.io/en/services/standard_modes.html>"]
2816pub enum MavStandardMode {
2817 #[doc = "Non standard mode. This may be used when reporting the mode if the current flight mode is not a standard mode."]
2818 MAV_STANDARD_MODE_NON_STANDARD = 0,
2819 #[doc = "Position mode (manual). Position-controlled and stabilized manual mode. When sticks are released vehicles return to their level-flight orientation and hold both position and altitude against wind and external forces. This mode can only be set by vehicles that can hold a fixed position. Multicopter (MC) vehicles actively brake and hold both position and altitude against wind and external forces. Hybrid MC/FW (\"VTOL\") vehicles first transition to multicopter mode (if needed) but otherwise behave in the same way as MC vehicles. Fixed-wing (FW) vehicles must not support this mode. Other vehicle types must not support this mode (this may be revisited through the PR process)."]
2820 MAV_STANDARD_MODE_POSITION_HOLD = 1,
2821 #[doc = "Orbit (manual). Position-controlled and stabilized manual mode. The vehicle circles around a fixed setpoint in the horizontal plane at a particular radius, altitude, and direction. Flight stacks may further allow manual control over the setpoint position, radius, direction, speed, and/or altitude of the circle, but this is not mandated. Flight stacks may support the [MAV_CMD_DO_ORBIT](<https://mavlink.io/en/messages/common.html#MAV_CMD_DO_ORBIT>) for changing the orbit parameters. MC and FW vehicles may support this mode. Hybrid MC/FW (\"VTOL\") vehicles may support this mode in MC/FW or both modes; if the mode is not supported by the current configuration the vehicle should transition to the supported configuration. Other vehicle types must not support this mode (this may be revisited through the PR process)."]
2822 MAV_STANDARD_MODE_ORBIT = 2,
2823 #[doc = "Cruise mode (manual). Position-controlled and stabilized manual mode. When sticks are released vehicles return to their level-flight orientation and hold their original track against wind and external forces. Fixed-wing (FW) vehicles level orientation and maintain current track and altitude against wind and external forces. Hybrid MC/FW (\"VTOL\") vehicles first transition to FW mode (if needed) but otherwise behave in the same way as MC vehicles. Multicopter (MC) vehicles must not support this mode. Other vehicle types must not support this mode (this may be revisited through the PR process)."]
2824 MAV_STANDARD_MODE_CRUISE = 3,
2825 #[doc = "Altitude hold (manual). Altitude-controlled and stabilized manual mode. When sticks are released vehicles return to their level-flight orientation and hold their altitude. MC vehicles continue with existing momentum and may move with wind (or other external forces). FW vehicles continue with current heading, but may be moved off-track by wind. Hybrid MC/FW (\"VTOL\") vehicles behave according to their current configuration/mode (FW or MC). Other vehicle types must not support this mode (this may be revisited through the PR process)."]
2826 MAV_STANDARD_MODE_ALTITUDE_HOLD = 4,
2827 #[doc = "Safe recovery mode (auto). Automatic mode that takes vehicle to a predefined safe location via a safe flight path, and may also automatically land the vehicle. This mode is more commonly referred to as RTL and/or or Smart RTL. The precise return location, flight path, and landing behaviour depend on vehicle configuration and type. For example, the vehicle might return to the home/launch location, a rally point, or the start of a mission landing, it might follow a direct path, mission path, or breadcrumb path, and land using a mission landing pattern or some other kind of descent."]
2828 MAV_STANDARD_MODE_SAFE_RECOVERY = 5,
2829 #[doc = "Mission mode (automatic). Automatic mode that executes MAVLink missions. Missions are executed from the current waypoint as soon as the mode is enabled."]
2830 MAV_STANDARD_MODE_MISSION = 6,
2831 #[doc = "Land mode (auto). Automatic mode that lands the vehicle at the current location. The precise landing behaviour depends on vehicle configuration and type."]
2832 MAV_STANDARD_MODE_LAND = 7,
2833 #[doc = "Takeoff mode (auto). Automatic takeoff mode. The precise takeoff behaviour depends on vehicle configuration and type."]
2834 MAV_STANDARD_MODE_TAKEOFF = 8,
2835}
2836impl MavStandardMode {
2837 pub const DEFAULT: Self = Self::MAV_STANDARD_MODE_NON_STANDARD;
2838}
2839impl Default for MavStandardMode {
2840 fn default() -> Self {
2841 Self::DEFAULT
2842 }
2843}
2844#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2845#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2846#[cfg_attr(feature = "serde", serde(tag = "type"))]
2847#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2848#[repr(u32)]
2849#[doc = "Possible responses from a WIFI_CONFIG_AP message."]
2850pub enum WifiConfigApResponse {
2851 #[doc = "Undefined response. Likely an indicative of a system that doesn't support this request."]
2852 WIFI_CONFIG_AP_RESPONSE_UNDEFINED = 0,
2853 #[doc = "Changes accepted."]
2854 WIFI_CONFIG_AP_RESPONSE_ACCEPTED = 1,
2855 #[doc = "Changes rejected."]
2856 WIFI_CONFIG_AP_RESPONSE_REJECTED = 2,
2857 #[doc = "Invalid Mode."]
2858 WIFI_CONFIG_AP_RESPONSE_MODE_ERROR = 3,
2859 #[doc = "Invalid SSID."]
2860 WIFI_CONFIG_AP_RESPONSE_SSID_ERROR = 4,
2861 #[doc = "Invalid Password."]
2862 WIFI_CONFIG_AP_RESPONSE_PASSWORD_ERROR = 5,
2863}
2864impl WifiConfigApResponse {
2865 pub const DEFAULT: Self = Self::WIFI_CONFIG_AP_RESPONSE_UNDEFINED;
2866}
2867impl Default for WifiConfigApResponse {
2868 fn default() -> Self {
2869 Self::DEFAULT
2870 }
2871}
2872#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2873#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2874#[cfg_attr(feature = "serde", serde(tag = "type"))]
2875#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2876#[repr(u32)]
2877#[doc = "Indicates the severity level, generally used for status messages to indicate their relative urgency. Based on RFC-5424 using expanded definitions at: <http://www.kiwisyslog.com/kb/info:-syslog-message-levels/>."]
2878pub enum MavSeverity {
2879 #[doc = "System is unusable. This is a \"panic\" condition."]
2880 MAV_SEVERITY_EMERGENCY = 0,
2881 #[doc = "Action should be taken immediately. Indicates error in non-critical systems."]
2882 MAV_SEVERITY_ALERT = 1,
2883 #[doc = "Action must be taken immediately. Indicates failure in a primary system."]
2884 MAV_SEVERITY_CRITICAL = 2,
2885 #[doc = "Indicates an error in secondary/redundant systems."]
2886 MAV_SEVERITY_ERROR = 3,
2887 #[doc = "Indicates about a possible future error if this is not resolved within a given timeframe. Example would be a low battery warning."]
2888 MAV_SEVERITY_WARNING = 4,
2889 #[doc = "An unusual event has occurred, though not an error condition. This should be investigated for the root cause."]
2890 MAV_SEVERITY_NOTICE = 5,
2891 #[doc = "Normal operational messages. Useful for logging. No action is required for these messages."]
2892 MAV_SEVERITY_INFO = 6,
2893 #[doc = "Useful non-operational messages that can assist in debugging. These should not occur during normal operation."]
2894 MAV_SEVERITY_DEBUG = 7,
2895}
2896impl MavSeverity {
2897 pub const DEFAULT: Self = Self::MAV_SEVERITY_EMERGENCY;
2898}
2899impl Default for MavSeverity {
2900 fn default() -> Self {
2901 Self::DEFAULT
2902 }
2903}
2904#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2905#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2906#[cfg_attr(feature = "serde", serde(tag = "type"))]
2907#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2908#[repr(u32)]
2909pub enum MavTunnelPayloadType {
2910 #[doc = "Encoding of payload unknown."]
2911 MAV_TUNNEL_PAYLOAD_TYPE_UNKNOWN = 0,
2912 #[doc = "Registered for STorM32 gimbal controller."]
2913 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED0 = 200,
2914 #[doc = "Registered for STorM32 gimbal controller."]
2915 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED1 = 201,
2916 #[doc = "Registered for STorM32 gimbal controller."]
2917 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED2 = 202,
2918 #[doc = "Registered for STorM32 gimbal controller."]
2919 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED3 = 203,
2920 #[doc = "Registered for STorM32 gimbal controller."]
2921 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED4 = 204,
2922 #[doc = "Registered for STorM32 gimbal controller."]
2923 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED5 = 205,
2924 #[doc = "Registered for STorM32 gimbal controller."]
2925 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED6 = 206,
2926 #[doc = "Registered for STorM32 gimbal controller."]
2927 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED7 = 207,
2928 #[doc = "Registered for STorM32 gimbal controller."]
2929 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED8 = 208,
2930 #[doc = "Registered for STorM32 gimbal controller."]
2931 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED9 = 209,
2932 #[doc = "Registered for ModalAI remote OSD protocol."]
2933 MAV_TUNNEL_PAYLOAD_TYPE_MODALAI_REMOTE_OSD = 210,
2934 #[doc = "Registered for ModalAI ESC UART passthru protocol."]
2935 MAV_TUNNEL_PAYLOAD_TYPE_MODALAI_ESC_UART_PASSTHRU = 211,
2936 #[doc = "Registered for ModalAI vendor use."]
2937 MAV_TUNNEL_PAYLOAD_TYPE_MODALAI_IO_UART_PASSTHRU = 212,
2938}
2939impl MavTunnelPayloadType {
2940 pub const DEFAULT: Self = Self::MAV_TUNNEL_PAYLOAD_TYPE_UNKNOWN;
2941}
2942impl Default for MavTunnelPayloadType {
2943 fn default() -> Self {
2944 Self::DEFAULT
2945 }
2946}
2947#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2948#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2949#[cfg_attr(feature = "serde", serde(tag = "type"))]
2950#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2951#[repr(u32)]
2952#[doc = "Generalized UAVCAN node health"]
2953pub enum UavcanNodeHealth {
2954 #[doc = "The node is functioning properly."]
2955 UAVCAN_NODE_HEALTH_OK = 0,
2956 #[doc = "A critical parameter went out of range or the node has encountered a minor failure."]
2957 UAVCAN_NODE_HEALTH_WARNING = 1,
2958 #[doc = "The node has encountered a major failure."]
2959 UAVCAN_NODE_HEALTH_ERROR = 2,
2960 #[doc = "The node has suffered a fatal malfunction."]
2961 UAVCAN_NODE_HEALTH_CRITICAL = 3,
2962}
2963impl UavcanNodeHealth {
2964 pub const DEFAULT: Self = Self::UAVCAN_NODE_HEALTH_OK;
2965}
2966impl Default for UavcanNodeHealth {
2967 fn default() -> Self {
2968 Self::DEFAULT
2969 }
2970}
2971#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2972#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2973#[cfg_attr(feature = "serde", serde(tag = "type"))]
2974#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2975#[repr(u32)]
2976#[doc = "Cellular network radio type"]
2977pub enum CellularNetworkRadioType {
2978 CELLULAR_NETWORK_RADIO_TYPE_NONE = 0,
2979 CELLULAR_NETWORK_RADIO_TYPE_GSM = 1,
2980 CELLULAR_NETWORK_RADIO_TYPE_CDMA = 2,
2981 CELLULAR_NETWORK_RADIO_TYPE_WCDMA = 3,
2982 CELLULAR_NETWORK_RADIO_TYPE_LTE = 4,
2983}
2984impl CellularNetworkRadioType {
2985 pub const DEFAULT: Self = Self::CELLULAR_NETWORK_RADIO_TYPE_NONE;
2986}
2987impl Default for CellularNetworkRadioType {
2988 fn default() -> Self {
2989 Self::DEFAULT
2990 }
2991}
2992#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2993#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2994#[cfg_attr(feature = "serde", serde(tag = "type"))]
2995#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2996#[repr(u32)]
2997pub enum MavOdidTimeAcc {
2998 #[doc = "The timestamp accuracy is unknown."]
2999 MAV_ODID_TIME_ACC_UNKNOWN = 0,
3000 #[doc = "The timestamp accuracy is smaller than or equal to 0.1 second."]
3001 MAV_ODID_TIME_ACC_0_1_SECOND = 1,
3002 #[doc = "The timestamp accuracy is smaller than or equal to 0.2 second."]
3003 MAV_ODID_TIME_ACC_0_2_SECOND = 2,
3004 #[doc = "The timestamp accuracy is smaller than or equal to 0.3 second."]
3005 MAV_ODID_TIME_ACC_0_3_SECOND = 3,
3006 #[doc = "The timestamp accuracy is smaller than or equal to 0.4 second."]
3007 MAV_ODID_TIME_ACC_0_4_SECOND = 4,
3008 #[doc = "The timestamp accuracy is smaller than or equal to 0.5 second."]
3009 MAV_ODID_TIME_ACC_0_5_SECOND = 5,
3010 #[doc = "The timestamp accuracy is smaller than or equal to 0.6 second."]
3011 MAV_ODID_TIME_ACC_0_6_SECOND = 6,
3012 #[doc = "The timestamp accuracy is smaller than or equal to 0.7 second."]
3013 MAV_ODID_TIME_ACC_0_7_SECOND = 7,
3014 #[doc = "The timestamp accuracy is smaller than or equal to 0.8 second."]
3015 MAV_ODID_TIME_ACC_0_8_SECOND = 8,
3016 #[doc = "The timestamp accuracy is smaller than or equal to 0.9 second."]
3017 MAV_ODID_TIME_ACC_0_9_SECOND = 9,
3018 #[doc = "The timestamp accuracy is smaller than or equal to 1.0 second."]
3019 MAV_ODID_TIME_ACC_1_0_SECOND = 10,
3020 #[doc = "The timestamp accuracy is smaller than or equal to 1.1 second."]
3021 MAV_ODID_TIME_ACC_1_1_SECOND = 11,
3022 #[doc = "The timestamp accuracy is smaller than or equal to 1.2 second."]
3023 MAV_ODID_TIME_ACC_1_2_SECOND = 12,
3024 #[doc = "The timestamp accuracy is smaller than or equal to 1.3 second."]
3025 MAV_ODID_TIME_ACC_1_3_SECOND = 13,
3026 #[doc = "The timestamp accuracy is smaller than or equal to 1.4 second."]
3027 MAV_ODID_TIME_ACC_1_4_SECOND = 14,
3028 #[doc = "The timestamp accuracy is smaller than or equal to 1.5 second."]
3029 MAV_ODID_TIME_ACC_1_5_SECOND = 15,
3030}
3031impl MavOdidTimeAcc {
3032 pub const DEFAULT: Self = Self::MAV_ODID_TIME_ACC_UNKNOWN;
3033}
3034impl Default for MavOdidTimeAcc {
3035 fn default() -> Self {
3036 Self::DEFAULT
3037 }
3038}
3039#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3040#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3041#[cfg_attr(feature = "serde", serde(tag = "type"))]
3042#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3043#[repr(u32)]
3044pub enum MavOdidHorAcc {
3045 #[doc = "The horizontal accuracy is unknown."]
3046 MAV_ODID_HOR_ACC_UNKNOWN = 0,
3047 #[doc = "The horizontal accuracy is smaller than 10 Nautical Miles. 18.52 km."]
3048 MAV_ODID_HOR_ACC_10NM = 1,
3049 #[doc = "The horizontal accuracy is smaller than 4 Nautical Miles. 7.408 km."]
3050 MAV_ODID_HOR_ACC_4NM = 2,
3051 #[doc = "The horizontal accuracy is smaller than 2 Nautical Miles. 3.704 km."]
3052 MAV_ODID_HOR_ACC_2NM = 3,
3053 #[doc = "The horizontal accuracy is smaller than 1 Nautical Miles. 1.852 km."]
3054 MAV_ODID_HOR_ACC_1NM = 4,
3055 #[doc = "The horizontal accuracy is smaller than 0.5 Nautical Miles. 926 m."]
3056 MAV_ODID_HOR_ACC_0_5NM = 5,
3057 #[doc = "The horizontal accuracy is smaller than 0.3 Nautical Miles. 555.6 m."]
3058 MAV_ODID_HOR_ACC_0_3NM = 6,
3059 #[doc = "The horizontal accuracy is smaller than 0.1 Nautical Miles. 185.2 m."]
3060 MAV_ODID_HOR_ACC_0_1NM = 7,
3061 #[doc = "The horizontal accuracy is smaller than 0.05 Nautical Miles. 92.6 m."]
3062 MAV_ODID_HOR_ACC_0_05NM = 8,
3063 #[doc = "The horizontal accuracy is smaller than 30 meter."]
3064 MAV_ODID_HOR_ACC_30_METER = 9,
3065 #[doc = "The horizontal accuracy is smaller than 10 meter."]
3066 MAV_ODID_HOR_ACC_10_METER = 10,
3067 #[doc = "The horizontal accuracy is smaller than 3 meter."]
3068 MAV_ODID_HOR_ACC_3_METER = 11,
3069 #[doc = "The horizontal accuracy is smaller than 1 meter."]
3070 MAV_ODID_HOR_ACC_1_METER = 12,
3071}
3072impl MavOdidHorAcc {
3073 pub const DEFAULT: Self = Self::MAV_ODID_HOR_ACC_UNKNOWN;
3074}
3075impl Default for MavOdidHorAcc {
3076 fn default() -> Self {
3077 Self::DEFAULT
3078 }
3079}
3080#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3081#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3082#[cfg_attr(feature = "serde", serde(tag = "type"))]
3083#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3084#[repr(u32)]
3085pub enum NavVtolLandOptions {
3086 #[doc = "Default autopilot landing behaviour."]
3087 NAV_VTOL_LAND_OPTIONS_DEFAULT = 0,
3088 #[doc = "Descend in fixed wing mode, transitioning to multicopter mode for vertical landing when close to the ground. The fixed wing descent pattern is at the discretion of the vehicle (e.g. transition altitude, loiter direction, radius, and speed, etc.)."]
3089 NAV_VTOL_LAND_OPTIONS_FW_DESCENT = 1,
3090 #[doc = "Land in multicopter mode on reaching the landing coordinates (the whole landing is by \"hover descent\")."]
3091 NAV_VTOL_LAND_OPTIONS_HOVER_DESCENT = 2,
3092}
3093impl NavVtolLandOptions {
3094 pub const DEFAULT: Self = Self::NAV_VTOL_LAND_OPTIONS_DEFAULT;
3095}
3096impl Default for NavVtolLandOptions {
3097 fn default() -> Self {
3098 Self::DEFAULT
3099 }
3100}
3101bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags to report failure cases over the high latency telemetry."] pub struct HlFailureFlag : u16 { # [doc = "GPS failure."] const HL_FAILURE_FLAG_GPS = 1 ; # [doc = "Differential pressure sensor failure."] const HL_FAILURE_FLAG_DIFFERENTIAL_PRESSURE = 2 ; # [doc = "Absolute pressure sensor failure."] const HL_FAILURE_FLAG_ABSOLUTE_PRESSURE = 4 ; # [doc = "Accelerometer sensor failure."] const HL_FAILURE_FLAG_3D_ACCEL = 8 ; # [doc = "Gyroscope sensor failure."] const HL_FAILURE_FLAG_3D_GYRO = 16 ; # [doc = "Magnetometer sensor failure."] const HL_FAILURE_FLAG_3D_MAG = 32 ; # [doc = "Terrain subsystem failure."] const HL_FAILURE_FLAG_TERRAIN = 64 ; # [doc = "Battery failure/critical low battery."] const HL_FAILURE_FLAG_BATTERY = 128 ; # [doc = "RC receiver failure/no RC connection."] const HL_FAILURE_FLAG_RC_RECEIVER = 256 ; # [doc = "Offboard link failure."] const HL_FAILURE_FLAG_OFFBOARD_LINK = 512 ; # [doc = "Engine failure."] const HL_FAILURE_FLAG_ENGINE = 1024 ; # [doc = "Geofence violation."] const HL_FAILURE_FLAG_GEOFENCE = 2048 ; # [doc = "Estimator failure, for example measurement rejection or large variances."] const HL_FAILURE_FLAG_ESTIMATOR = 4096 ; # [doc = "Mission failure."] const HL_FAILURE_FLAG_MISSION = 8192 ; } }
3102impl HlFailureFlag {
3103 pub const DEFAULT: Self = Self::HL_FAILURE_FLAG_GPS;
3104}
3105impl Default for HlFailureFlag {
3106 fn default() -> Self {
3107 Self::DEFAULT
3108 }
3109}
3110bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags in the HIL_SENSOR message indicate which fields have updated since the last message"] pub struct HilSensorUpdatedFlags : u32 { # [doc = "The value in the xacc field has been updated"] const HIL_SENSOR_UPDATED_XACC = 1 ; # [doc = "The value in the yacc field has been updated"] const HIL_SENSOR_UPDATED_YACC = 2 ; # [doc = "The value in the zacc field has been updated"] const HIL_SENSOR_UPDATED_ZACC = 4 ; # [doc = "The value in the xgyro field has been updated"] const HIL_SENSOR_UPDATED_XGYRO = 8 ; # [doc = "The value in the ygyro field has been updated"] const HIL_SENSOR_UPDATED_YGYRO = 16 ; # [doc = "The value in the zgyro field has been updated"] const HIL_SENSOR_UPDATED_ZGYRO = 32 ; # [doc = "The value in the xmag field has been updated"] const HIL_SENSOR_UPDATED_XMAG = 64 ; # [doc = "The value in the ymag field has been updated"] const HIL_SENSOR_UPDATED_YMAG = 128 ; # [doc = "The value in the zmag field has been updated"] const HIL_SENSOR_UPDATED_ZMAG = 256 ; # [doc = "The value in the abs_pressure field has been updated"] const HIL_SENSOR_UPDATED_ABS_PRESSURE = 512 ; # [doc = "The value in the diff_pressure field has been updated"] const HIL_SENSOR_UPDATED_DIFF_PRESSURE = 1024 ; # [doc = "The value in the pressure_alt field has been updated"] const HIL_SENSOR_UPDATED_PRESSURE_ALT = 2048 ; # [doc = "The value in the temperature field has been updated"] const HIL_SENSOR_UPDATED_TEMPERATURE = 4096 ; # [doc = "Full reset of attitude/position/velocities/etc was performed in sim (Bit 31)."] const HIL_SENSOR_UPDATED_RESET = 2147483648 ; } }
3111impl HilSensorUpdatedFlags {
3112 pub const DEFAULT: Self = Self::HIL_SENSOR_UPDATED_XACC;
3113}
3114impl Default for HilSensorUpdatedFlags {
3115 fn default() -> Self {
3116 Self::DEFAULT
3117 }
3118}
3119#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3120#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3121#[cfg_attr(feature = "serde", serde(tag = "type"))]
3122#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3123#[repr(u32)]
3124#[doc = "Actions that may be specified in MAV_CMD_OVERRIDE_GOTO to override mission execution."]
3125pub enum MavGoto {
3126 #[doc = "Hold at the current position."]
3127 MAV_GOTO_DO_HOLD = 0,
3128 #[doc = "Continue with the next item in mission execution."]
3129 MAV_GOTO_DO_CONTINUE = 1,
3130 #[doc = "Hold at the current position of the system"]
3131 MAV_GOTO_HOLD_AT_CURRENT_POSITION = 2,
3132 #[doc = "Hold at the position specified in the parameters of the DO_HOLD action"]
3133 MAV_GOTO_HOLD_AT_SPECIFIED_POSITION = 3,
3134}
3135impl MavGoto {
3136 pub const DEFAULT: Self = Self::MAV_GOTO_DO_HOLD;
3137}
3138impl Default for MavGoto {
3139 fn default() -> Self {
3140 Self::DEFAULT
3141 }
3142}
3143bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Winch status flags used in WINCH_STATUS"] pub struct MavWinchStatusFlag : u32 { # [doc = "Winch is healthy"] const MAV_WINCH_STATUS_HEALTHY = 1 ; # [doc = "Winch line is fully retracted"] const MAV_WINCH_STATUS_FULLY_RETRACTED = 2 ; # [doc = "Winch motor is moving"] const MAV_WINCH_STATUS_MOVING = 4 ; # [doc = "Winch clutch is engaged allowing motor to move freely."] const MAV_WINCH_STATUS_CLUTCH_ENGAGED = 8 ; # [doc = "Winch is locked by locking mechanism."] const MAV_WINCH_STATUS_LOCKED = 16 ; # [doc = "Winch is gravity dropping payload."] const MAV_WINCH_STATUS_DROPPING = 32 ; # [doc = "Winch is arresting payload descent."] const MAV_WINCH_STATUS_ARRESTING = 64 ; # [doc = "Winch is using torque measurements to sense the ground."] const MAV_WINCH_STATUS_GROUND_SENSE = 128 ; # [doc = "Winch is returning to the fully retracted position."] const MAV_WINCH_STATUS_RETRACTING = 256 ; # [doc = "Winch is redelivering the payload. This is a failover state if the line tension goes above a threshold during RETRACTING."] const MAV_WINCH_STATUS_REDELIVER = 512 ; # [doc = "Winch is abandoning the line and possibly payload. Winch unspools the entire calculated line length. This is a failover state from REDELIVER if the number of attempts exceeds a threshold."] const MAV_WINCH_STATUS_ABANDON_LINE = 1024 ; # [doc = "Winch is engaging the locking mechanism."] const MAV_WINCH_STATUS_LOCKING = 2048 ; # [doc = "Winch is spooling on line."] const MAV_WINCH_STATUS_LOAD_LINE = 4096 ; # [doc = "Winch is loading a payload."] const MAV_WINCH_STATUS_LOAD_PAYLOAD = 8192 ; } }
3144impl MavWinchStatusFlag {
3145 pub const DEFAULT: Self = Self::MAV_WINCH_STATUS_HEALTHY;
3146}
3147impl Default for MavWinchStatusFlag {
3148 fn default() -> Self {
3149 Self::DEFAULT
3150 }
3151}
3152#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3153#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3154#[cfg_attr(feature = "serde", serde(tag = "type"))]
3155#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3156#[repr(u32)]
3157#[doc = "SERIAL_CONTROL device types"]
3158pub enum SerialControlDev {
3159 #[doc = "First telemetry port"]
3160 SERIAL_CONTROL_DEV_TELEM1 = 0,
3161 #[doc = "Second telemetry port"]
3162 SERIAL_CONTROL_DEV_TELEM2 = 1,
3163 #[doc = "First GPS port"]
3164 SERIAL_CONTROL_DEV_GPS1 = 2,
3165 #[doc = "Second GPS port"]
3166 SERIAL_CONTROL_DEV_GPS2 = 3,
3167 #[doc = "system shell"]
3168 SERIAL_CONTROL_DEV_SHELL = 10,
3169 #[doc = "SERIAL0"]
3170 SERIAL_CONTROL_SERIAL0 = 100,
3171 #[doc = "SERIAL1"]
3172 SERIAL_CONTROL_SERIAL1 = 101,
3173 #[doc = "SERIAL2"]
3174 SERIAL_CONTROL_SERIAL2 = 102,
3175 #[doc = "SERIAL3"]
3176 SERIAL_CONTROL_SERIAL3 = 103,
3177 #[doc = "SERIAL4"]
3178 SERIAL_CONTROL_SERIAL4 = 104,
3179 #[doc = "SERIAL5"]
3180 SERIAL_CONTROL_SERIAL5 = 105,
3181 #[doc = "SERIAL6"]
3182 SERIAL_CONTROL_SERIAL6 = 106,
3183 #[doc = "SERIAL7"]
3184 SERIAL_CONTROL_SERIAL7 = 107,
3185 #[doc = "SERIAL8"]
3186 SERIAL_CONTROL_SERIAL8 = 108,
3187 #[doc = "SERIAL9"]
3188 SERIAL_CONTROL_SERIAL9 = 109,
3189}
3190impl SerialControlDev {
3191 pub const DEFAULT: Self = Self::SERIAL_CONTROL_DEV_TELEM1;
3192}
3193impl Default for SerialControlDev {
3194 fn default() -> Self {
3195 Self::DEFAULT
3196 }
3197}
3198bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags in ESTIMATOR_STATUS message"] pub struct EstimatorStatusFlags : u16 { # [doc = "True if the attitude estimate is good"] const ESTIMATOR_ATTITUDE = 1 ; # [doc = "True if the horizontal velocity estimate is good"] const ESTIMATOR_VELOCITY_HORIZ = 2 ; # [doc = "True if the vertical velocity estimate is good"] const ESTIMATOR_VELOCITY_VERT = 4 ; # [doc = "True if the horizontal position (relative) estimate is good"] const ESTIMATOR_POS_HORIZ_REL = 8 ; # [doc = "True if the horizontal position (absolute) estimate is good"] const ESTIMATOR_POS_HORIZ_ABS = 16 ; # [doc = "True if the vertical position (absolute) estimate is good"] const ESTIMATOR_POS_VERT_ABS = 32 ; # [doc = "True if the vertical position (above ground) estimate is good"] const ESTIMATOR_POS_VERT_AGL = 64 ; # [doc = "True if the EKF is in a constant position mode and is not using external measurements (eg GPS or optical flow)"] const ESTIMATOR_CONST_POS_MODE = 128 ; # [doc = "True if the EKF has sufficient data to enter a mode that will provide a (relative) position estimate"] const ESTIMATOR_PRED_POS_HORIZ_REL = 256 ; # [doc = "True if the EKF has sufficient data to enter a mode that will provide a (absolute) position estimate"] const ESTIMATOR_PRED_POS_HORIZ_ABS = 512 ; # [doc = "True if the EKF has detected a GPS glitch"] const ESTIMATOR_GPS_GLITCH = 1024 ; # [doc = "True if the EKF has detected bad accelerometer data"] const ESTIMATOR_ACCEL_ERROR = 2048 ; } }
3199impl EstimatorStatusFlags {
3200 pub const DEFAULT: Self = Self::ESTIMATOR_ATTITUDE;
3201}
3202impl Default for EstimatorStatusFlags {
3203 fn default() -> Self {
3204 Self::DEFAULT
3205 }
3206}
3207#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3208#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3209#[cfg_attr(feature = "serde", serde(tag = "type"))]
3210#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3211#[repr(u32)]
3212#[doc = "Coordinate frames used by MAVLink. Not all frames are supported by all commands, messages, or vehicles. Global frames use the following naming conventions: - \"GLOBAL\": Global coordinate frame with WGS84 latitude/longitude and altitude positive over mean sea level (MSL) by default. The following modifiers may be used with \"GLOBAL\": - \"RELATIVE_ALT\": Altitude is relative to the vehicle home position rather than MSL. - \"TERRAIN_ALT\": Altitude is relative to ground level rather than MSL. - \"INT\": Latitude/longitude (in degrees) are scaled by multiplying by 1E7. Local frames use the following naming conventions: - \"LOCAL\": Origin of local frame is fixed relative to earth. Unless otherwise specified this origin is the origin of the vehicle position-estimator (\"EKF\"). - \"BODY\": Origin of local frame travels with the vehicle. NOTE, \"BODY\" does NOT indicate alignment of frame axis with vehicle attitude. - \"OFFSET\": Deprecated synonym for \"BODY\" (origin travels with the vehicle). Not to be used for new frames. Some deprecated frames do not follow these conventions (e.g. MAV_FRAME_BODY_NED and MAV_FRAME_BODY_OFFSET_NED)."]
3213pub enum MavFrame {
3214 #[doc = "Global (WGS84) coordinate frame + altitude relative to mean sea level (MSL)."]
3215 MAV_FRAME_GLOBAL = 0,
3216 #[doc = "NED local tangent frame (x: North, y: East, z: Down) with origin fixed relative to earth."]
3217 MAV_FRAME_LOCAL_NED = 1,
3218 #[doc = "NOT a coordinate frame, indicates a mission command."]
3219 MAV_FRAME_MISSION = 2,
3220 #[doc = "Global (WGS84) coordinate frame + altitude relative to the home position."]
3221 MAV_FRAME_GLOBAL_RELATIVE_ALT = 3,
3222 #[doc = "ENU local tangent frame (x: East, y: North, z: Up) with origin fixed relative to earth."]
3223 MAV_FRAME_LOCAL_ENU = 4,
3224 #[doc = "Global (WGS84) coordinate frame (scaled) + altitude relative to mean sea level (MSL)."]
3225 MAV_FRAME_GLOBAL_INT = 5,
3226 #[doc = "Global (WGS84) coordinate frame (scaled) + altitude relative to the home position."]
3227 MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6,
3228 #[doc = "NED local tangent frame (x: North, y: East, z: Down) with origin that travels with the vehicle."]
3229 MAV_FRAME_LOCAL_OFFSET_NED = 7,
3230 #[doc = "Same as MAV_FRAME_LOCAL_NED when used to represent position values. Same as MAV_FRAME_BODY_FRD when used with velocity/acceleration values."]
3231 MAV_FRAME_BODY_NED = 8,
3232 #[doc = "This is the same as MAV_FRAME_BODY_FRD."]
3233 MAV_FRAME_BODY_OFFSET_NED = 9,
3234 #[doc = "Global (WGS84) coordinate frame with AGL altitude (altitude at ground level)."]
3235 MAV_FRAME_GLOBAL_TERRAIN_ALT = 10,
3236 #[doc = "Global (WGS84) coordinate frame (scaled) with AGL altitude (altitude at ground level)."]
3237 MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11,
3238 #[doc = "FRD local frame aligned to the vehicle's attitude (x: Forward, y: Right, z: Down) with an origin that travels with vehicle."]
3239 MAV_FRAME_BODY_FRD = 12,
3240 #[doc = "MAV_FRAME_BODY_FLU - Body fixed frame of reference, Z-up (x: Forward, y: Left, z: Up)."]
3241 MAV_FRAME_RESERVED_13 = 13,
3242 #[doc = "MAV_FRAME_MOCAP_NED - Odometry local coordinate frame of data given by a motion capture system, Z-down (x: North, y: East, z: Down)."]
3243 MAV_FRAME_RESERVED_14 = 14,
3244 #[doc = "MAV_FRAME_MOCAP_ENU - Odometry local coordinate frame of data given by a motion capture system, Z-up (x: East, y: North, z: Up)."]
3245 MAV_FRAME_RESERVED_15 = 15,
3246 #[doc = "MAV_FRAME_VISION_NED - Odometry local coordinate frame of data given by a vision estimation system, Z-down (x: North, y: East, z: Down)."]
3247 MAV_FRAME_RESERVED_16 = 16,
3248 #[doc = "MAV_FRAME_VISION_ENU - Odometry local coordinate frame of data given by a vision estimation system, Z-up (x: East, y: North, z: Up)."]
3249 MAV_FRAME_RESERVED_17 = 17,
3250 #[doc = "MAV_FRAME_ESTIM_NED - Odometry local coordinate frame of data given by an estimator running onboard the vehicle, Z-down (x: North, y: East, z: Down)."]
3251 MAV_FRAME_RESERVED_18 = 18,
3252 #[doc = "MAV_FRAME_ESTIM_ENU - Odometry local coordinate frame of data given by an estimator running onboard the vehicle, Z-up (x: East, y: North, z: Up)."]
3253 MAV_FRAME_RESERVED_19 = 19,
3254 #[doc = "FRD local tangent frame (x: Forward, y: Right, z: Down) with origin fixed relative to earth. The forward axis is aligned to the front of the vehicle in the horizontal plane."]
3255 MAV_FRAME_LOCAL_FRD = 20,
3256 #[doc = "FLU local tangent frame (x: Forward, y: Left, z: Up) with origin fixed relative to earth. The forward axis is aligned to the front of the vehicle in the horizontal plane."]
3257 MAV_FRAME_LOCAL_FLU = 21,
3258}
3259impl MavFrame {
3260 pub const DEFAULT: Self = Self::MAV_FRAME_GLOBAL;
3261}
3262impl Default for MavFrame {
3263 fn default() -> Self {
3264 Self::DEFAULT
3265 }
3266}
3267#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3268#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3269#[cfg_attr(feature = "serde", serde(tag = "type"))]
3270#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3271#[repr(u32)]
3272#[doc = "These flags encode the cellular network status"]
3273pub enum CellularStatusFlag {
3274 #[doc = "State unknown or not reportable."]
3275 CELLULAR_STATUS_FLAG_UNKNOWN = 0,
3276 #[doc = "Modem is unusable"]
3277 CELLULAR_STATUS_FLAG_FAILED = 1,
3278 #[doc = "Modem is being initialized"]
3279 CELLULAR_STATUS_FLAG_INITIALIZING = 2,
3280 #[doc = "Modem is locked"]
3281 CELLULAR_STATUS_FLAG_LOCKED = 3,
3282 #[doc = "Modem is not enabled and is powered down"]
3283 CELLULAR_STATUS_FLAG_DISABLED = 4,
3284 #[doc = "Modem is currently transitioning to the CELLULAR_STATUS_FLAG_DISABLED state"]
3285 CELLULAR_STATUS_FLAG_DISABLING = 5,
3286 #[doc = "Modem is currently transitioning to the CELLULAR_STATUS_FLAG_ENABLED state"]
3287 CELLULAR_STATUS_FLAG_ENABLING = 6,
3288 #[doc = "Modem is enabled and powered on but not registered with a network provider and not available for data connections"]
3289 CELLULAR_STATUS_FLAG_ENABLED = 7,
3290 #[doc = "Modem is searching for a network provider to register"]
3291 CELLULAR_STATUS_FLAG_SEARCHING = 8,
3292 #[doc = "Modem is registered with a network provider, and data connections and messaging may be available for use"]
3293 CELLULAR_STATUS_FLAG_REGISTERED = 9,
3294 #[doc = "Modem is disconnecting and deactivating the last active packet data bearer. This state will not be entered if more than one packet data bearer is active and one of the active bearers is deactivated"]
3295 CELLULAR_STATUS_FLAG_DISCONNECTING = 10,
3296 #[doc = "Modem is activating and connecting the first packet data bearer. Subsequent bearer activations when another bearer is already active do not cause this state to be entered"]
3297 CELLULAR_STATUS_FLAG_CONNECTING = 11,
3298 #[doc = "One or more packet data bearers is active and connected"]
3299 CELLULAR_STATUS_FLAG_CONNECTED = 12,
3300}
3301impl CellularStatusFlag {
3302 pub const DEFAULT: Self = Self::CELLULAR_STATUS_FLAG_UNKNOWN;
3303}
3304impl Default for CellularStatusFlag {
3305 fn default() -> Self {
3306 Self::DEFAULT
3307 }
3308}
3309#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3310#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3311#[cfg_attr(feature = "serde", serde(tag = "type"))]
3312#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3313#[repr(u32)]
3314#[doc = "MAV FTP error codes (<https://mavlink.io/en/services/ftp.html>)"]
3315pub enum MavFtpErr {
3316 #[doc = "None: No error"]
3317 MAV_FTP_ERR_NONE = 0,
3318 #[doc = "Fail: Unknown failure"]
3319 MAV_FTP_ERR_FAIL = 1,
3320 #[doc = "FailErrno: Command failed, Err number sent back in PayloadHeader.data[1]. \t\tThis is a file-system error number understood by the server operating system."]
3321 MAV_FTP_ERR_FAILERRNO = 2,
3322 #[doc = "InvalidDataSize: Payload size is invalid"]
3323 MAV_FTP_ERR_INVALIDDATASIZE = 3,
3324 #[doc = "InvalidSession: Session is not currently open"]
3325 MAV_FTP_ERR_INVALIDSESSION = 4,
3326 #[doc = "NoSessionsAvailable: All available sessions are already in use"]
3327 MAV_FTP_ERR_NOSESSIONSAVAILABLE = 5,
3328 #[doc = "EOF: Offset past end of file for ListDirectory and ReadFile commands"]
3329 MAV_FTP_ERR_EOF = 6,
3330 #[doc = "UnknownCommand: Unknown command / opcode"]
3331 MAV_FTP_ERR_UNKNOWNCOMMAND = 7,
3332 #[doc = "FileExists: File/directory already exists"]
3333 MAV_FTP_ERR_FILEEXISTS = 8,
3334 #[doc = "FileProtected: File/directory is write protected"]
3335 MAV_FTP_ERR_FILEPROTECTED = 9,
3336 #[doc = "FileNotFound: File/directory not found"]
3337 MAV_FTP_ERR_FILENOTFOUND = 10,
3338}
3339impl MavFtpErr {
3340 pub const DEFAULT: Self = Self::MAV_FTP_ERR_NONE;
3341}
3342impl Default for MavFtpErr {
3343 fn default() -> Self {
3344 Self::DEFAULT
3345 }
3346}
3347#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3348#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3349#[cfg_attr(feature = "serde", serde(tag = "type"))]
3350#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3351#[repr(u32)]
3352#[doc = "Enumeration of battery functions"]
3353pub enum MavBatteryFunction {
3354 #[doc = "Battery function is unknown"]
3355 MAV_BATTERY_FUNCTION_UNKNOWN = 0,
3356 #[doc = "Battery supports all flight systems"]
3357 MAV_BATTERY_FUNCTION_ALL = 1,
3358 #[doc = "Battery for the propulsion system"]
3359 MAV_BATTERY_FUNCTION_PROPULSION = 2,
3360 #[doc = "Avionics battery"]
3361 MAV_BATTERY_FUNCTION_AVIONICS = 3,
3362 #[doc = "Payload battery"]
3363 MAV_BATTERY_FUNCTION_PAYLOAD = 4,
3364}
3365impl MavBatteryFunction {
3366 pub const DEFAULT: Self = Self::MAV_BATTERY_FUNCTION_UNKNOWN;
3367}
3368impl Default for MavBatteryFunction {
3369 fn default() -> Self {
3370 Self::DEFAULT
3371 }
3372}
3373bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "SERIAL_CONTROL flags (bitmask)"] pub struct SerialControlFlag : u8 { # [doc = "Set if this is a reply"] const SERIAL_CONTROL_FLAG_REPLY = 1 ; # [doc = "Set if the sender wants the receiver to send a response as another SERIAL_CONTROL message"] const SERIAL_CONTROL_FLAG_RESPOND = 2 ; # [doc = "Set if access to the serial port should be removed from whatever driver is currently using it, giving exclusive access to the SERIAL_CONTROL protocol. The port can be handed back by sending a request without this flag set"] const SERIAL_CONTROL_FLAG_EXCLUSIVE = 4 ; # [doc = "Block on writes to the serial port"] const SERIAL_CONTROL_FLAG_BLOCKING = 8 ; # [doc = "Send multiple replies until port is drained"] const SERIAL_CONTROL_FLAG_MULTI = 16 ; } }
3374impl SerialControlFlag {
3375 pub const DEFAULT: Self = Self::SERIAL_CONTROL_FLAG_REPLY;
3376}
3377impl Default for SerialControlFlag {
3378 fn default() -> Self {
3379 Self::DEFAULT
3380 }
3381}
3382#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3383#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3384#[cfg_attr(feature = "serde", serde(tag = "type"))]
3385#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3386#[repr(u32)]
3387pub enum MavOdidStatus {
3388 #[doc = "The status of the (UA) Unmanned Aircraft is undefined."]
3389 MAV_ODID_STATUS_UNDECLARED = 0,
3390 #[doc = "The UA is on the ground."]
3391 MAV_ODID_STATUS_GROUND = 1,
3392 #[doc = "The UA is in the air."]
3393 MAV_ODID_STATUS_AIRBORNE = 2,
3394 #[doc = "The UA is having an emergency."]
3395 MAV_ODID_STATUS_EMERGENCY = 3,
3396 #[doc = "The remote ID system is failing or unreliable in some way."]
3397 MAV_ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE = 4,
3398}
3399impl MavOdidStatus {
3400 pub const DEFAULT: Self = Self::MAV_ODID_STATUS_UNDECLARED;
3401}
3402impl Default for MavOdidStatus {
3403 fn default() -> Self {
3404 Self::DEFAULT
3405 }
3406}
3407#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3408#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3409#[cfg_attr(feature = "serde", serde(tag = "type"))]
3410#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3411#[repr(u32)]
3412#[doc = "Actuator configuration, used to change a setting on an actuator. Component information metadata can be used to know which outputs support which commands."]
3413pub enum ActuatorConfiguration {
3414 #[doc = "Do nothing."]
3415 ACTUATOR_CONFIGURATION_NONE = 0,
3416 #[doc = "Command the actuator to beep now."]
3417 ACTUATOR_CONFIGURATION_BEEP = 1,
3418 #[doc = "Permanently set the actuator (ESC) to 3D mode (reversible thrust)."]
3419 ACTUATOR_CONFIGURATION_3D_MODE_ON = 2,
3420 #[doc = "Permanently set the actuator (ESC) to non 3D mode (non-reversible thrust)."]
3421 ACTUATOR_CONFIGURATION_3D_MODE_OFF = 3,
3422 #[doc = "Permanently set the actuator (ESC) to spin direction 1 (which can be clockwise or counter-clockwise)."]
3423 ACTUATOR_CONFIGURATION_SPIN_DIRECTION1 = 4,
3424 #[doc = "Permanently set the actuator (ESC) to spin direction 2 (opposite of direction 1)."]
3425 ACTUATOR_CONFIGURATION_SPIN_DIRECTION2 = 5,
3426}
3427impl ActuatorConfiguration {
3428 pub const DEFAULT: Self = Self::ACTUATOR_CONFIGURATION_NONE;
3429}
3430impl Default for ActuatorConfiguration {
3431 fn default() -> Self {
3432 Self::DEFAULT
3433 }
3434}
3435#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3436#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3437#[cfg_attr(feature = "serde", serde(tag = "type"))]
3438#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3439#[repr(u32)]
3440pub enum MavState {
3441 #[doc = "Uninitialized system, state is unknown."]
3442 MAV_STATE_UNINIT = 0,
3443 #[doc = "System is booting up."]
3444 MAV_STATE_BOOT = 1,
3445 #[doc = "System is calibrating and not flight-ready."]
3446 MAV_STATE_CALIBRATING = 2,
3447 #[doc = "System is grounded and on standby. It can be launched any time."]
3448 MAV_STATE_STANDBY = 3,
3449 #[doc = "System is active and might be already airborne. Motors are engaged."]
3450 MAV_STATE_ACTIVE = 4,
3451 #[doc = "System is in a non-normal flight mode (failsafe). It can however still navigate."]
3452 MAV_STATE_CRITICAL = 5,
3453 #[doc = "System is in a non-normal flight mode (failsafe). It lost control over parts or over the whole airframe. It is in mayday and going down."]
3454 MAV_STATE_EMERGENCY = 6,
3455 #[doc = "System just initialized its power-down sequence, will shut down now."]
3456 MAV_STATE_POWEROFF = 7,
3457 #[doc = "System is terminating itself (failsafe or commanded)."]
3458 MAV_STATE_FLIGHT_TERMINATION = 8,
3459}
3460impl MavState {
3461 pub const DEFAULT: Self = Self::MAV_STATE_UNINIT;
3462}
3463impl Default for MavState {
3464 fn default() -> Self {
3465 Self::DEFAULT
3466 }
3467}
3468#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3469#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3470#[cfg_attr(feature = "serde", serde(tag = "type"))]
3471#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3472#[repr(u32)]
3473#[doc = "Camera tracking status flags"]
3474pub enum CameraTrackingStatusFlags {
3475 #[doc = "Camera is not tracking"]
3476 CAMERA_TRACKING_STATUS_FLAGS_IDLE = 0,
3477 #[doc = "Camera is tracking"]
3478 CAMERA_TRACKING_STATUS_FLAGS_ACTIVE = 1,
3479 #[doc = "Camera tracking in error state"]
3480 CAMERA_TRACKING_STATUS_FLAGS_ERROR = 2,
3481}
3482impl CameraTrackingStatusFlags {
3483 pub const DEFAULT: Self = Self::CAMERA_TRACKING_STATUS_FLAGS_IDLE;
3484}
3485impl Default for CameraTrackingStatusFlags {
3486 fn default() -> Self {
3487 Self::DEFAULT
3488 }
3489}
3490#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3491#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3492#[cfg_attr(feature = "serde", serde(tag = "type"))]
3493#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3494#[repr(u32)]
3495#[doc = "Flags to indicate the status of camera storage."]
3496pub enum StorageStatus {
3497 #[doc = "Storage is missing (no microSD card loaded for example.)"]
3498 STORAGE_STATUS_EMPTY = 0,
3499 #[doc = "Storage present but unformatted."]
3500 STORAGE_STATUS_UNFORMATTED = 1,
3501 #[doc = "Storage present and ready."]
3502 STORAGE_STATUS_READY = 2,
3503 #[doc = "Camera does not supply storage status information. Capacity information in STORAGE_INFORMATION fields will be ignored."]
3504 STORAGE_STATUS_NOT_SUPPORTED = 3,
3505}
3506impl StorageStatus {
3507 pub const DEFAULT: Self = Self::STORAGE_STATUS_EMPTY;
3508}
3509impl Default for StorageStatus {
3510 fn default() -> Self {
3511 Self::DEFAULT
3512 }
3513}
3514#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3515#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3516#[cfg_attr(feature = "serde", serde(tag = "type"))]
3517#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3518#[repr(u32)]
3519pub enum MavOdidClassEu {
3520 #[doc = "The class for the UA, according to the EU specification, is undeclared."]
3521 MAV_ODID_CLASS_EU_UNDECLARED = 0,
3522 #[doc = "The class for the UA, according to the EU specification, is Class 0."]
3523 MAV_ODID_CLASS_EU_CLASS_0 = 1,
3524 #[doc = "The class for the UA, according to the EU specification, is Class 1."]
3525 MAV_ODID_CLASS_EU_CLASS_1 = 2,
3526 #[doc = "The class for the UA, according to the EU specification, is Class 2."]
3527 MAV_ODID_CLASS_EU_CLASS_2 = 3,
3528 #[doc = "The class for the UA, according to the EU specification, is Class 3."]
3529 MAV_ODID_CLASS_EU_CLASS_3 = 4,
3530 #[doc = "The class for the UA, according to the EU specification, is Class 4."]
3531 MAV_ODID_CLASS_EU_CLASS_4 = 5,
3532 #[doc = "The class for the UA, according to the EU specification, is Class 5."]
3533 MAV_ODID_CLASS_EU_CLASS_5 = 6,
3534 #[doc = "The class for the UA, according to the EU specification, is Class 6."]
3535 MAV_ODID_CLASS_EU_CLASS_6 = 7,
3536}
3537impl MavOdidClassEu {
3538 pub const DEFAULT: Self = Self::MAV_ODID_CLASS_EU_UNDECLARED;
3539}
3540impl Default for MavOdidClassEu {
3541 fn default() -> Self {
3542 Self::DEFAULT
3543 }
3544}
3545#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3546#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3547#[cfg_attr(feature = "serde", serde(tag = "type"))]
3548#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3549#[repr(u32)]
3550#[doc = "Possible safety switch states."]
3551pub enum SafetySwitchState {
3552 #[doc = "Safety switch is engaged and vehicle should be safe to approach."]
3553 SAFETY_SWITCH_STATE_SAFE = 0,
3554 #[doc = "Safety switch is NOT engaged and motors, propellers and other actuators should be considered active."]
3555 SAFETY_SWITCH_STATE_DANGEROUS = 1,
3556}
3557impl SafetySwitchState {
3558 pub const DEFAULT: Self = Self::SAFETY_SWITCH_STATE_SAFE;
3559}
3560impl Default for SafetySwitchState {
3561 fn default() -> Self {
3562 Self::DEFAULT
3563 }
3564}
3565bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] pub struct GpsInputIgnoreFlags : u16 { # [doc = "ignore altitude field"] const GPS_INPUT_IGNORE_FLAG_ALT = 1 ; # [doc = "ignore hdop field"] const GPS_INPUT_IGNORE_FLAG_HDOP = 2 ; # [doc = "ignore vdop field"] const GPS_INPUT_IGNORE_FLAG_VDOP = 4 ; # [doc = "ignore horizontal velocity field (vn and ve)"] const GPS_INPUT_IGNORE_FLAG_VEL_HORIZ = 8 ; # [doc = "ignore vertical velocity field (vd)"] const GPS_INPUT_IGNORE_FLAG_VEL_VERT = 16 ; # [doc = "ignore speed accuracy field"] const GPS_INPUT_IGNORE_FLAG_SPEED_ACCURACY = 32 ; # [doc = "ignore horizontal accuracy field"] const GPS_INPUT_IGNORE_FLAG_HORIZONTAL_ACCURACY = 64 ; # [doc = "ignore vertical accuracy field"] const GPS_INPUT_IGNORE_FLAG_VERTICAL_ACCURACY = 128 ; } }
3566impl GpsInputIgnoreFlags {
3567 pub const DEFAULT: Self = Self::GPS_INPUT_IGNORE_FLAG_ALT;
3568}
3569impl Default for GpsInputIgnoreFlags {
3570 fn default() -> Self {
3571 Self::DEFAULT
3572 }
3573}
3574#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3575#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3576#[cfg_attr(feature = "serde", serde(tag = "type"))]
3577#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3578#[repr(u32)]
3579#[doc = "Actions for reading and writing plan information (mission, rally points, geofence) between persistent and volatile storage when using MAV_CMD_PREFLIGHT_STORAGE. (Commonly missions are loaded from persistent storage (flash/EEPROM) into volatile storage (RAM) on startup and written back when they are changed.)"]
3580pub enum PreflightStorageMissionAction {
3581 #[doc = "Read current mission data from persistent storage"]
3582 MISSION_READ_PERSISTENT = 0,
3583 #[doc = "Write current mission data to persistent storage"]
3584 MISSION_WRITE_PERSISTENT = 1,
3585 #[doc = "Erase all mission data stored on the vehicle (both persistent and volatile storage)"]
3586 MISSION_RESET_DEFAULT = 2,
3587}
3588impl PreflightStorageMissionAction {
3589 pub const DEFAULT: Self = Self::MISSION_READ_PERSISTENT;
3590}
3591impl Default for PreflightStorageMissionAction {
3592 fn default() -> Self {
3593 Self::DEFAULT
3594 }
3595}
3596#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3597#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3598#[cfg_attr(feature = "serde", serde(tag = "type"))]
3599#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3600#[repr(u32)]
3601#[doc = "Source of information about this collision."]
3602pub enum MavCollisionSrc {
3603 #[doc = "ID field references ADSB_VEHICLE packets"]
3604 MAV_COLLISION_SRC_ADSB = 0,
3605 #[doc = "ID field references MAVLink SRC ID"]
3606 MAV_COLLISION_SRC_MAVLINK_GPS_GLOBAL_INT = 1,
3607}
3608impl MavCollisionSrc {
3609 pub const DEFAULT: Self = Self::MAV_COLLISION_SRC_ADSB;
3610}
3611impl Default for MavCollisionSrc {
3612 fn default() -> Self {
3613 Self::DEFAULT
3614 }
3615}
3616#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3617#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3618#[cfg_attr(feature = "serde", serde(tag = "type"))]
3619#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3620#[repr(u32)]
3621#[doc = "States of the mission state machine. Note that these states are independent of whether the mission is in a mode that can execute mission items or not (is suspended). They may not all be relevant on all vehicles."]
3622pub enum MissionState {
3623 #[doc = "The mission status reporting is not supported."]
3624 MISSION_STATE_UNKNOWN = 0,
3625 #[doc = "No mission on the vehicle."]
3626 MISSION_STATE_NO_MISSION = 1,
3627 #[doc = "Mission has not started. This is the case after a mission has uploaded but not yet started executing."]
3628 MISSION_STATE_NOT_STARTED = 2,
3629 #[doc = "Mission is active, and will execute mission items when in auto mode."]
3630 MISSION_STATE_ACTIVE = 3,
3631 #[doc = "Mission is paused when in auto mode."]
3632 MISSION_STATE_PAUSED = 4,
3633 #[doc = "Mission has executed all mission items."]
3634 MISSION_STATE_COMPLETE = 5,
3635}
3636impl MissionState {
3637 pub const DEFAULT: Self = Self::MISSION_STATE_UNKNOWN;
3638}
3639impl Default for MissionState {
3640 fn default() -> Self {
3641 Self::DEFAULT
3642 }
3643}
3644bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Bitmap to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 9 is set the floats afx afy afz should be interpreted as force instead of acceleration."] pub struct PositionTargetTypemask : u16 { # [doc = "Ignore position x"] const POSITION_TARGET_TYPEMASK_X_IGNORE = 1 ; # [doc = "Ignore position y"] const POSITION_TARGET_TYPEMASK_Y_IGNORE = 2 ; # [doc = "Ignore position z"] const POSITION_TARGET_TYPEMASK_Z_IGNORE = 4 ; # [doc = "Ignore velocity x"] const POSITION_TARGET_TYPEMASK_VX_IGNORE = 8 ; # [doc = "Ignore velocity y"] const POSITION_TARGET_TYPEMASK_VY_IGNORE = 16 ; # [doc = "Ignore velocity z"] const POSITION_TARGET_TYPEMASK_VZ_IGNORE = 32 ; # [doc = "Ignore acceleration x"] const POSITION_TARGET_TYPEMASK_AX_IGNORE = 64 ; # [doc = "Ignore acceleration y"] const POSITION_TARGET_TYPEMASK_AY_IGNORE = 128 ; # [doc = "Ignore acceleration z"] const POSITION_TARGET_TYPEMASK_AZ_IGNORE = 256 ; # [doc = "Use force instead of acceleration"] const POSITION_TARGET_TYPEMASK_FORCE_SET = 512 ; # [doc = "Ignore yaw"] const POSITION_TARGET_TYPEMASK_YAW_IGNORE = 1024 ; # [doc = "Ignore yaw rate"] const POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE = 2048 ; } }
3645impl PositionTargetTypemask {
3646 pub const DEFAULT: Self = Self::POSITION_TARGET_TYPEMASK_X_IGNORE;
3647}
3648impl Default for PositionTargetTypemask {
3649 fn default() -> Self {
3650 Self::DEFAULT
3651 }
3652}
3653bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Power supply status flags (bitmask)"] pub struct MavPowerStatus : u16 { # [doc = "main brick power supply valid"] const MAV_POWER_STATUS_BRICK_VALID = 1 ; # [doc = "main servo power supply valid for FMU"] const MAV_POWER_STATUS_SERVO_VALID = 2 ; # [doc = "USB power is connected"] const MAV_POWER_STATUS_USB_CONNECTED = 4 ; # [doc = "peripheral supply is in over-current state"] const MAV_POWER_STATUS_PERIPH_OVERCURRENT = 8 ; # [doc = "hi-power peripheral supply is in over-current state"] const MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT = 16 ; # [doc = "Power status has changed since boot"] const MAV_POWER_STATUS_CHANGED = 32 ; } }
3654impl MavPowerStatus {
3655 pub const DEFAULT: Self = Self::MAV_POWER_STATUS_BRICK_VALID;
3656}
3657impl Default for MavPowerStatus {
3658 fn default() -> Self {
3659 Self::DEFAULT
3660 }
3661}
3662#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3663#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3664#[cfg_attr(feature = "serde", serde(tag = "type"))]
3665#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3666#[repr(u32)]
3667pub enum MavOdidOperatorLocationType {
3668 #[doc = "The location/altitude of the operator is the same as the take-off location."]
3669 MAV_ODID_OPERATOR_LOCATION_TYPE_TAKEOFF = 0,
3670 #[doc = "The location/altitude of the operator is dynamic. E.g. based on live GNSS data."]
3671 MAV_ODID_OPERATOR_LOCATION_TYPE_LIVE_GNSS = 1,
3672 #[doc = "The location/altitude of the operator are fixed values."]
3673 MAV_ODID_OPERATOR_LOCATION_TYPE_FIXED = 2,
3674}
3675impl MavOdidOperatorLocationType {
3676 pub const DEFAULT: Self = Self::MAV_ODID_OPERATOR_LOCATION_TYPE_TAKEOFF;
3677}
3678impl Default for MavOdidOperatorLocationType {
3679 fn default() -> Self {
3680 Self::DEFAULT
3681 }
3682}
3683#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3684#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3685#[cfg_attr(feature = "serde", serde(tag = "type"))]
3686#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3687#[repr(u32)]
3688#[doc = "Reason for an event error response."]
3689pub enum MavEventErrorReason {
3690 #[doc = "The requested event is not available (anymore)."]
3691 MAV_EVENT_ERROR_REASON_UNAVAILABLE = 0,
3692}
3693impl MavEventErrorReason {
3694 pub const DEFAULT: Self = Self::MAV_EVENT_ERROR_REASON_UNAVAILABLE;
3695}
3696impl Default for MavEventErrorReason {
3697 fn default() -> Self {
3698 Self::DEFAULT
3699 }
3700}
3701#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3702#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3703#[cfg_attr(feature = "serde", serde(tag = "type"))]
3704#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3705#[repr(u32)]
3706#[doc = "Actuator output function. Values greater or equal to 1000 are autopilot-specific."]
3707pub enum ActuatorOutputFunction {
3708 #[doc = "No function (disabled)."]
3709 ACTUATOR_OUTPUT_FUNCTION_NONE = 0,
3710 #[doc = "Motor 1"]
3711 ACTUATOR_OUTPUT_FUNCTION_MOTOR1 = 1,
3712 #[doc = "Motor 2"]
3713 ACTUATOR_OUTPUT_FUNCTION_MOTOR2 = 2,
3714 #[doc = "Motor 3"]
3715 ACTUATOR_OUTPUT_FUNCTION_MOTOR3 = 3,
3716 #[doc = "Motor 4"]
3717 ACTUATOR_OUTPUT_FUNCTION_MOTOR4 = 4,
3718 #[doc = "Motor 5"]
3719 ACTUATOR_OUTPUT_FUNCTION_MOTOR5 = 5,
3720 #[doc = "Motor 6"]
3721 ACTUATOR_OUTPUT_FUNCTION_MOTOR6 = 6,
3722 #[doc = "Motor 7"]
3723 ACTUATOR_OUTPUT_FUNCTION_MOTOR7 = 7,
3724 #[doc = "Motor 8"]
3725 ACTUATOR_OUTPUT_FUNCTION_MOTOR8 = 8,
3726 #[doc = "Motor 9"]
3727 ACTUATOR_OUTPUT_FUNCTION_MOTOR9 = 9,
3728 #[doc = "Motor 10"]
3729 ACTUATOR_OUTPUT_FUNCTION_MOTOR10 = 10,
3730 #[doc = "Motor 11"]
3731 ACTUATOR_OUTPUT_FUNCTION_MOTOR11 = 11,
3732 #[doc = "Motor 12"]
3733 ACTUATOR_OUTPUT_FUNCTION_MOTOR12 = 12,
3734 #[doc = "Motor 13"]
3735 ACTUATOR_OUTPUT_FUNCTION_MOTOR13 = 13,
3736 #[doc = "Motor 14"]
3737 ACTUATOR_OUTPUT_FUNCTION_MOTOR14 = 14,
3738 #[doc = "Motor 15"]
3739 ACTUATOR_OUTPUT_FUNCTION_MOTOR15 = 15,
3740 #[doc = "Motor 16"]
3741 ACTUATOR_OUTPUT_FUNCTION_MOTOR16 = 16,
3742 #[doc = "Servo 1"]
3743 ACTUATOR_OUTPUT_FUNCTION_SERVO1 = 33,
3744 #[doc = "Servo 2"]
3745 ACTUATOR_OUTPUT_FUNCTION_SERVO2 = 34,
3746 #[doc = "Servo 3"]
3747 ACTUATOR_OUTPUT_FUNCTION_SERVO3 = 35,
3748 #[doc = "Servo 4"]
3749 ACTUATOR_OUTPUT_FUNCTION_SERVO4 = 36,
3750 #[doc = "Servo 5"]
3751 ACTUATOR_OUTPUT_FUNCTION_SERVO5 = 37,
3752 #[doc = "Servo 6"]
3753 ACTUATOR_OUTPUT_FUNCTION_SERVO6 = 38,
3754 #[doc = "Servo 7"]
3755 ACTUATOR_OUTPUT_FUNCTION_SERVO7 = 39,
3756 #[doc = "Servo 8"]
3757 ACTUATOR_OUTPUT_FUNCTION_SERVO8 = 40,
3758 #[doc = "Servo 9"]
3759 ACTUATOR_OUTPUT_FUNCTION_SERVO9 = 41,
3760 #[doc = "Servo 10"]
3761 ACTUATOR_OUTPUT_FUNCTION_SERVO10 = 42,
3762 #[doc = "Servo 11"]
3763 ACTUATOR_OUTPUT_FUNCTION_SERVO11 = 43,
3764 #[doc = "Servo 12"]
3765 ACTUATOR_OUTPUT_FUNCTION_SERVO12 = 44,
3766 #[doc = "Servo 13"]
3767 ACTUATOR_OUTPUT_FUNCTION_SERVO13 = 45,
3768 #[doc = "Servo 14"]
3769 ACTUATOR_OUTPUT_FUNCTION_SERVO14 = 46,
3770 #[doc = "Servo 15"]
3771 ACTUATOR_OUTPUT_FUNCTION_SERVO15 = 47,
3772 #[doc = "Servo 16"]
3773 ACTUATOR_OUTPUT_FUNCTION_SERVO16 = 48,
3774}
3775impl ActuatorOutputFunction {
3776 pub const DEFAULT: Self = Self::ACTUATOR_OUTPUT_FUNCTION_NONE;
3777}
3778impl Default for ActuatorOutputFunction {
3779 fn default() -> Self {
3780 Self::DEFAULT
3781 }
3782}
3783#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3784#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3785#[cfg_attr(feature = "serde", serde(tag = "type"))]
3786#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3787#[repr(u32)]
3788pub enum MavOdidDescType {
3789 #[doc = "Optional free-form text description of the purpose of the flight."]
3790 MAV_ODID_DESC_TYPE_TEXT = 0,
3791 #[doc = "Optional additional clarification when status == MAV_ODID_STATUS_EMERGENCY."]
3792 MAV_ODID_DESC_TYPE_EMERGENCY = 1,
3793 #[doc = "Optional additional clarification when status != MAV_ODID_STATUS_EMERGENCY."]
3794 MAV_ODID_DESC_TYPE_EXTENDED_STATUS = 2,
3795}
3796impl MavOdidDescType {
3797 pub const DEFAULT: Self = Self::MAV_ODID_DESC_TYPE_TEXT;
3798}
3799impl Default for MavOdidDescType {
3800 fn default() -> Self {
3801 Self::DEFAULT
3802 }
3803}
3804#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3805#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3806#[cfg_attr(feature = "serde", serde(tag = "type"))]
3807#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3808#[repr(u32)]
3809#[doc = "MAV FTP opcodes: <https://mavlink.io/en/services/ftp.html>"]
3810pub enum MavFtpOpcode {
3811 #[doc = "None. Ignored, always ACKed"]
3812 MAV_FTP_OPCODE_NONE = 0,
3813 #[doc = "TerminateSession: Terminates open Read session"]
3814 MAV_FTP_OPCODE_TERMINATESESSION = 1,
3815 #[doc = "ResetSessions: Terminates all open read sessions"]
3816 MAV_FTP_OPCODE_RESETSESSION = 2,
3817 #[doc = "ListDirectory. List files and directories in path from offset"]
3818 MAV_FTP_OPCODE_LISTDIRECTORY = 3,
3819 #[doc = "OpenFileRO: Opens file at path for reading, returns session"]
3820 MAV_FTP_OPCODE_OPENFILERO = 4,
3821 #[doc = "ReadFile: Reads size bytes from offset in session"]
3822 MAV_FTP_OPCODE_READFILE = 5,
3823 #[doc = "CreateFile: Creates file at path for writing, returns session"]
3824 MAV_FTP_OPCODE_CREATEFILE = 6,
3825 #[doc = "WriteFile: Writes size bytes to offset in session"]
3826 MAV_FTP_OPCODE_WRITEFILE = 7,
3827 #[doc = "RemoveFile: Remove file at path"]
3828 MAV_FTP_OPCODE_REMOVEFILE = 8,
3829 #[doc = "CreateDirectory: Creates directory at path"]
3830 MAV_FTP_OPCODE_CREATEDIRECTORY = 9,
3831 #[doc = "RemoveDirectory: Removes directory at path. The directory must be empty."]
3832 MAV_FTP_OPCODE_REMOVEDIRECTORY = 10,
3833 #[doc = "OpenFileWO: Opens file at path for writing, returns session"]
3834 MAV_FTP_OPCODE_OPENFILEWO = 11,
3835 #[doc = "TruncateFile: Truncate file at path to offset length"]
3836 MAV_FTP_OPCODE_TRUNCATEFILE = 12,
3837 #[doc = "Rename: Rename path1 to path2"]
3838 MAV_FTP_OPCODE_RENAME = 13,
3839 #[doc = "CalcFileCRC32: Calculate CRC32 for file at path"]
3840 MAV_FTP_OPCODE_CALCFILECRC = 14,
3841 #[doc = "BurstReadFile: Burst download session file"]
3842 MAV_FTP_OPCODE_BURSTREADFILE = 15,
3843 #[doc = "ACK: ACK response"]
3844 MAV_FTP_OPCODE_ACK = 128,
3845 #[doc = "NAK: NAK response"]
3846 MAV_FTP_OPCODE_NAK = 129,
3847}
3848impl MavFtpOpcode {
3849 pub const DEFAULT: Self = Self::MAV_FTP_OPCODE_NONE;
3850}
3851impl Default for MavFtpOpcode {
3852 fn default() -> Self {
3853 Self::DEFAULT
3854 }
3855}
3856#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3857#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3858#[cfg_attr(feature = "serde", serde(tag = "type"))]
3859#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3860#[repr(u32)]
3861#[doc = "Type of AIS vessel, enum duplicated from AIS standard, <https://gpsd.gitlab.io/gpsd/AIVDM.html>"]
3862pub enum AisType {
3863 #[doc = "Not available (default)."]
3864 AIS_TYPE_UNKNOWN = 0,
3865 AIS_TYPE_RESERVED_1 = 1,
3866 AIS_TYPE_RESERVED_2 = 2,
3867 AIS_TYPE_RESERVED_3 = 3,
3868 AIS_TYPE_RESERVED_4 = 4,
3869 AIS_TYPE_RESERVED_5 = 5,
3870 AIS_TYPE_RESERVED_6 = 6,
3871 AIS_TYPE_RESERVED_7 = 7,
3872 AIS_TYPE_RESERVED_8 = 8,
3873 AIS_TYPE_RESERVED_9 = 9,
3874 AIS_TYPE_RESERVED_10 = 10,
3875 AIS_TYPE_RESERVED_11 = 11,
3876 AIS_TYPE_RESERVED_12 = 12,
3877 AIS_TYPE_RESERVED_13 = 13,
3878 AIS_TYPE_RESERVED_14 = 14,
3879 AIS_TYPE_RESERVED_15 = 15,
3880 AIS_TYPE_RESERVED_16 = 16,
3881 AIS_TYPE_RESERVED_17 = 17,
3882 AIS_TYPE_RESERVED_18 = 18,
3883 AIS_TYPE_RESERVED_19 = 19,
3884 #[doc = "Wing In Ground effect."]
3885 AIS_TYPE_WIG = 20,
3886 AIS_TYPE_WIG_HAZARDOUS_A = 21,
3887 AIS_TYPE_WIG_HAZARDOUS_B = 22,
3888 AIS_TYPE_WIG_HAZARDOUS_C = 23,
3889 AIS_TYPE_WIG_HAZARDOUS_D = 24,
3890 AIS_TYPE_WIG_RESERVED_1 = 25,
3891 AIS_TYPE_WIG_RESERVED_2 = 26,
3892 AIS_TYPE_WIG_RESERVED_3 = 27,
3893 AIS_TYPE_WIG_RESERVED_4 = 28,
3894 AIS_TYPE_WIG_RESERVED_5 = 29,
3895 AIS_TYPE_FISHING = 30,
3896 AIS_TYPE_TOWING = 31,
3897 #[doc = "Towing: length exceeds 200m or breadth exceeds 25m."]
3898 AIS_TYPE_TOWING_LARGE = 32,
3899 #[doc = "Dredging or other underwater ops."]
3900 AIS_TYPE_DREDGING = 33,
3901 AIS_TYPE_DIVING = 34,
3902 AIS_TYPE_MILITARY = 35,
3903 AIS_TYPE_SAILING = 36,
3904 AIS_TYPE_PLEASURE = 37,
3905 AIS_TYPE_RESERVED_20 = 38,
3906 AIS_TYPE_RESERVED_21 = 39,
3907 #[doc = "High Speed Craft."]
3908 AIS_TYPE_HSC = 40,
3909 AIS_TYPE_HSC_HAZARDOUS_A = 41,
3910 AIS_TYPE_HSC_HAZARDOUS_B = 42,
3911 AIS_TYPE_HSC_HAZARDOUS_C = 43,
3912 AIS_TYPE_HSC_HAZARDOUS_D = 44,
3913 AIS_TYPE_HSC_RESERVED_1 = 45,
3914 AIS_TYPE_HSC_RESERVED_2 = 46,
3915 AIS_TYPE_HSC_RESERVED_3 = 47,
3916 AIS_TYPE_HSC_RESERVED_4 = 48,
3917 AIS_TYPE_HSC_UNKNOWN = 49,
3918 AIS_TYPE_PILOT = 50,
3919 #[doc = "Search And Rescue vessel."]
3920 AIS_TYPE_SAR = 51,
3921 AIS_TYPE_TUG = 52,
3922 AIS_TYPE_PORT_TENDER = 53,
3923 #[doc = "Anti-pollution equipment."]
3924 AIS_TYPE_ANTI_POLLUTION = 54,
3925 AIS_TYPE_LAW_ENFORCEMENT = 55,
3926 AIS_TYPE_SPARE_LOCAL_1 = 56,
3927 AIS_TYPE_SPARE_LOCAL_2 = 57,
3928 AIS_TYPE_MEDICAL_TRANSPORT = 58,
3929 #[doc = "Noncombatant ship according to RR Resolution No. 18."]
3930 AIS_TYPE_NONECOMBATANT = 59,
3931 AIS_TYPE_PASSENGER = 60,
3932 AIS_TYPE_PASSENGER_HAZARDOUS_A = 61,
3933 AIS_TYPE_PASSENGER_HAZARDOUS_B = 62,
3934 AIS_TYPE_PASSENGER_HAZARDOUS_C = 63,
3935 AIS_TYPE_PASSENGER_HAZARDOUS_D = 64,
3936 AIS_TYPE_PASSENGER_RESERVED_1 = 65,
3937 AIS_TYPE_PASSENGER_RESERVED_2 = 66,
3938 AIS_TYPE_PASSENGER_RESERVED_3 = 67,
3939 AIS_TYPE_PASSENGER_RESERVED_4 = 68,
3940 AIS_TYPE_PASSENGER_UNKNOWN = 69,
3941 AIS_TYPE_CARGO = 70,
3942 AIS_TYPE_CARGO_HAZARDOUS_A = 71,
3943 AIS_TYPE_CARGO_HAZARDOUS_B = 72,
3944 AIS_TYPE_CARGO_HAZARDOUS_C = 73,
3945 AIS_TYPE_CARGO_HAZARDOUS_D = 74,
3946 AIS_TYPE_CARGO_RESERVED_1 = 75,
3947 AIS_TYPE_CARGO_RESERVED_2 = 76,
3948 AIS_TYPE_CARGO_RESERVED_3 = 77,
3949 AIS_TYPE_CARGO_RESERVED_4 = 78,
3950 AIS_TYPE_CARGO_UNKNOWN = 79,
3951 AIS_TYPE_TANKER = 80,
3952 AIS_TYPE_TANKER_HAZARDOUS_A = 81,
3953 AIS_TYPE_TANKER_HAZARDOUS_B = 82,
3954 AIS_TYPE_TANKER_HAZARDOUS_C = 83,
3955 AIS_TYPE_TANKER_HAZARDOUS_D = 84,
3956 AIS_TYPE_TANKER_RESERVED_1 = 85,
3957 AIS_TYPE_TANKER_RESERVED_2 = 86,
3958 AIS_TYPE_TANKER_RESERVED_3 = 87,
3959 AIS_TYPE_TANKER_RESERVED_4 = 88,
3960 AIS_TYPE_TANKER_UNKNOWN = 89,
3961 AIS_TYPE_OTHER = 90,
3962 AIS_TYPE_OTHER_HAZARDOUS_A = 91,
3963 AIS_TYPE_OTHER_HAZARDOUS_B = 92,
3964 AIS_TYPE_OTHER_HAZARDOUS_C = 93,
3965 AIS_TYPE_OTHER_HAZARDOUS_D = 94,
3966 AIS_TYPE_OTHER_RESERVED_1 = 95,
3967 AIS_TYPE_OTHER_RESERVED_2 = 96,
3968 AIS_TYPE_OTHER_RESERVED_3 = 97,
3969 AIS_TYPE_OTHER_RESERVED_4 = 98,
3970 AIS_TYPE_OTHER_UNKNOWN = 99,
3971}
3972impl AisType {
3973 pub const DEFAULT: Self = Self::AIS_TYPE_UNKNOWN;
3974}
3975impl Default for AisType {
3976 fn default() -> Self {
3977 Self::DEFAULT
3978 }
3979}
3980bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "These encode the sensors whose status is sent as part of the SYS_STATUS message in the extended fields."] pub struct MavSysStatusSensorExtended : u32 { # [doc = "0x01 Recovery system (parachute, balloon, retracts etc)"] const MAV_SYS_STATUS_RECOVERY_SYSTEM = 1 ; } }
3981impl MavSysStatusSensorExtended {
3982 pub const DEFAULT: Self = Self::MAV_SYS_STATUS_RECOVERY_SYSTEM;
3983}
3984impl Default for MavSysStatusSensorExtended {
3985 fn default() -> Self {
3986 Self::DEFAULT
3987 }
3988}
3989#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3990#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3991#[cfg_attr(feature = "serde", serde(tag = "type"))]
3992#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3993#[repr(u32)]
3994#[doc = "Supported component metadata types. These are used in the \"general\" metadata file returned by COMPONENT_METADATA to provide information about supported metadata types. The types are not used directly in MAVLink messages."]
3995pub enum CompMetadataType {
3996 #[doc = "General information about the component. General metadata includes information about other metadata types supported by the component. Files of this type must be supported, and must be downloadable from vehicle using a MAVLink FTP URI."]
3997 COMP_METADATA_TYPE_GENERAL = 0,
3998 #[doc = "Parameter meta data."]
3999 COMP_METADATA_TYPE_PARAMETER = 1,
4000 #[doc = "Meta data that specifies which commands and command parameters the vehicle supports. (WIP)"]
4001 COMP_METADATA_TYPE_COMMANDS = 2,
4002 #[doc = "Meta data that specifies external non-MAVLink peripherals."]
4003 COMP_METADATA_TYPE_PERIPHERALS = 3,
4004 #[doc = "Meta data for the events interface."]
4005 COMP_METADATA_TYPE_EVENTS = 4,
4006 #[doc = "Meta data for actuator configuration (motors, servos and vehicle geometry) and testing."]
4007 COMP_METADATA_TYPE_ACTUATORS = 5,
4008}
4009impl CompMetadataType {
4010 pub const DEFAULT: Self = Self::COMP_METADATA_TYPE_GENERAL;
4011}
4012impl Default for CompMetadataType {
4013 fn default() -> Self {
4014 Self::DEFAULT
4015 }
4016}
4017bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Bitmask of (optional) autopilot capabilities (64 bit). If a bit is set, the autopilot supports this capability."] pub struct MavProtocolCapability : u64 { # [doc = "Autopilot supports the MISSION_ITEM float message type. Note that MISSION_ITEM is deprecated, and autopilots should use MISSION_INT instead."] const MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT = 1 ; # [doc = "Autopilot supports the new param float message type."] const MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT = 2 ; # [doc = "Autopilot supports MISSION_ITEM_INT scaled integer message type. Note that this flag must always be set if missions are supported, because missions must always use MISSION_ITEM_INT (rather than MISSION_ITEM, which is deprecated)."] const MAV_PROTOCOL_CAPABILITY_MISSION_INT = 4 ; # [doc = "Autopilot supports COMMAND_INT scaled integer message type."] const MAV_PROTOCOL_CAPABILITY_COMMAND_INT = 8 ; # [doc = "Parameter protocol uses byte-wise encoding of parameter values into param_value (float) fields: <https://mavlink.io/en/services/parameter.html#parameter-encoding>. Note that either this flag or MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_C_CAST should be set if the parameter protocol is supported."] const MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_BYTEWISE = 16 ; # [doc = "Autopilot supports the File Transfer Protocol v1: <https://mavlink.io/en/services/ftp.html>."] const MAV_PROTOCOL_CAPABILITY_FTP = 32 ; # [doc = "Autopilot supports commanding attitude offboard."] const MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET = 64 ; # [doc = "Autopilot supports commanding position and velocity targets in local NED frame."] const MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED = 128 ; # [doc = "Autopilot supports commanding position and velocity targets in global scaled integers."] const MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT = 256 ; # [doc = "Autopilot supports terrain protocol / data handling."] const MAV_PROTOCOL_CAPABILITY_TERRAIN = 512 ; # [doc = "Reserved for future use."] const MAV_PROTOCOL_CAPABILITY_RESERVED3 = 1024 ; # [doc = "Autopilot supports the MAV_CMD_DO_FLIGHTTERMINATION command (flight termination)."] const MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION = 2048 ; # [doc = "Autopilot supports onboard compass calibration."] const MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION = 4096 ; # [doc = "Autopilot supports MAVLink version 2."] const MAV_PROTOCOL_CAPABILITY_MAVLINK2 = 8192 ; # [doc = "Autopilot supports mission fence protocol."] const MAV_PROTOCOL_CAPABILITY_MISSION_FENCE = 16384 ; # [doc = "Autopilot supports mission rally point protocol."] const MAV_PROTOCOL_CAPABILITY_MISSION_RALLY = 32768 ; # [doc = "Reserved for future use."] const MAV_PROTOCOL_CAPABILITY_RESERVED2 = 65536 ; # [doc = "Parameter protocol uses C-cast of parameter values to set the param_value (float) fields: <https://mavlink.io/en/services/parameter.html#parameter-encoding>. Note that either this flag or MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_BYTEWISE should be set if the parameter protocol is supported."] const MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_C_CAST = 131072 ; # [doc = "This component implements/is a gimbal manager. This means the GIMBAL_MANAGER_INFORMATION, and other messages can be requested."] const MAV_PROTOCOL_CAPABILITY_COMPONENT_IMPLEMENTS_GIMBAL_MANAGER = 262144 ; # [doc = "Component supports locking control to a particular GCS independent of its system (via MAV_CMD_REQUEST_OPERATOR_CONTROL)."] const MAV_PROTOCOL_CAPABILITY_COMPONENT_ACCEPTS_GCS_CONTROL = 524288 ; } }
4018impl MavProtocolCapability {
4019 pub const DEFAULT: Self = Self::MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT;
4020}
4021impl Default for MavProtocolCapability {
4022 fn default() -> Self {
4023 Self::DEFAULT
4024 }
4025}
4026#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4027#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4028#[cfg_attr(feature = "serde", serde(tag = "type"))]
4029#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4030#[repr(u32)]
4031#[doc = "These defines are predefined OR-combined mode flags. There is no need to use values from this enum, but it simplifies the use of the mode flags. Note that manual input is enabled in all modes as a safety override."]
4032pub enum MavMode {
4033 #[doc = "System is not ready to fly, booting, calibrating, etc. No flag is set."]
4034 MAV_MODE_PREFLIGHT = 0,
4035 #[doc = "System is allowed to be active, under assisted RC control."]
4036 MAV_MODE_STABILIZE_DISARMED = 80,
4037 #[doc = "System is allowed to be active, under assisted RC control."]
4038 MAV_MODE_STABILIZE_ARMED = 208,
4039 #[doc = "System is allowed to be active, under manual (RC) control, no stabilization"]
4040 MAV_MODE_MANUAL_DISARMED = 64,
4041 #[doc = "System is allowed to be active, under manual (RC) control, no stabilization"]
4042 MAV_MODE_MANUAL_ARMED = 192,
4043 #[doc = "System is allowed to be active, under autonomous control, manual setpoint"]
4044 MAV_MODE_GUIDED_DISARMED = 88,
4045 #[doc = "System is allowed to be active, under autonomous control, manual setpoint"]
4046 MAV_MODE_GUIDED_ARMED = 216,
4047 #[doc = "System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by waypoints)"]
4048 MAV_MODE_AUTO_DISARMED = 92,
4049 #[doc = "System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by waypoints)"]
4050 MAV_MODE_AUTO_ARMED = 220,
4051 #[doc = "UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only."]
4052 MAV_MODE_TEST_DISARMED = 66,
4053 #[doc = "UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only."]
4054 MAV_MODE_TEST_ARMED = 194,
4055}
4056impl MavMode {
4057 pub const DEFAULT: Self = Self::MAV_MODE_PREFLIGHT;
4058}
4059impl Default for MavMode {
4060 fn default() -> Self {
4061 Self::DEFAULT
4062 }
4063}
4064#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4065#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4066#[cfg_attr(feature = "serde", serde(tag = "type"))]
4067#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4068#[repr(u32)]
4069#[doc = "Tune formats (used for vehicle buzzer/tone generation)."]
4070pub enum TuneFormat {
4071 #[doc = "Format is QBasic 1.1 Play: <https://www.qbasic.net/en/reference/qb11/Statement/PLAY-006.htm>."]
4072 TUNE_FORMAT_QBASIC1_1 = 1,
4073 #[doc = "Format is Modern Music Markup Language (MML): <https://en.wikipedia.org/wiki/Music_Macro_Language#Modern_MML>."]
4074 TUNE_FORMAT_MML_MODERN = 2,
4075}
4076impl TuneFormat {
4077 pub const DEFAULT: Self = Self::TUNE_FORMAT_QBASIC1_1;
4078}
4079impl Default for TuneFormat {
4080 fn default() -> Self {
4081 Self::DEFAULT
4082 }
4083}
4084bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags for gimbal device (lower level) operation."] pub struct GimbalDeviceFlags : u16 { # [doc = "Set to retracted safe position (no stabilization), takes precedence over all other flags."] const GIMBAL_DEVICE_FLAGS_RETRACT = 1 ; # [doc = "Set to neutral/default position, taking precedence over all other flags except RETRACT. Neutral is commonly forward-facing and horizontal (roll=pitch=yaw=0) but may be any orientation."] const GIMBAL_DEVICE_FLAGS_NEUTRAL = 2 ; # [doc = "Lock roll angle to absolute angle relative to horizon (not relative to vehicle). This is generally the default with a stabilizing gimbal."] const GIMBAL_DEVICE_FLAGS_ROLL_LOCK = 4 ; # [doc = "Lock pitch angle to absolute angle relative to horizon (not relative to vehicle). This is generally the default with a stabilizing gimbal."] const GIMBAL_DEVICE_FLAGS_PITCH_LOCK = 8 ; # [doc = "Lock yaw angle to absolute angle relative to North (not relative to vehicle). If this flag is set, the yaw angle and z component of angular velocity are relative to North (earth frame, x-axis pointing North), else they are relative to the vehicle heading (vehicle frame, earth frame rotated so that the x-axis is pointing forward)."] const GIMBAL_DEVICE_FLAGS_YAW_LOCK = 16 ; # [doc = "Yaw angle and z component of angular velocity are relative to the vehicle heading (vehicle frame, earth frame rotated such that the x-axis is pointing forward)."] const GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME = 32 ; # [doc = "Yaw angle and z component of angular velocity are relative to North (earth frame, x-axis is pointing North)."] const GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME = 64 ; # [doc = "Gimbal device can accept yaw angle inputs relative to North (earth frame). This flag is only for reporting (attempts to set this flag are ignored)."] const GIMBAL_DEVICE_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME = 128 ; # [doc = "The gimbal orientation is set exclusively by the RC signals feed to the gimbal's radio control inputs. MAVLink messages for setting the gimbal orientation (GIMBAL_DEVICE_SET_ATTITUDE) are ignored."] const GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE = 256 ; # [doc = "The gimbal orientation is determined by combining/mixing the RC signals feed to the gimbal's radio control inputs and the MAVLink messages for setting the gimbal orientation (GIMBAL_DEVICE_SET_ATTITUDE). How these two controls are combined or mixed is not defined by the protocol but is up to the implementation."] const GIMBAL_DEVICE_FLAGS_RC_MIXED = 512 ; } }
4085impl GimbalDeviceFlags {
4086 pub const DEFAULT: Self = Self::GIMBAL_DEVICE_FLAGS_RETRACT;
4087}
4088impl Default for GimbalDeviceFlags {
4089 fn default() -> Self {
4090 Self::DEFAULT
4091 }
4092}
4093#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4094#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4095#[cfg_attr(feature = "serde", serde(tag = "type"))]
4096#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4097#[repr(u32)]
4098#[doc = "List of possible failure type to inject."]
4099pub enum FailureType {
4100 #[doc = "No failure injected, used to reset a previous failure."]
4101 FAILURE_TYPE_OK = 0,
4102 #[doc = "Sets unit off, so completely non-responsive."]
4103 FAILURE_TYPE_OFF = 1,
4104 #[doc = "Unit is stuck e.g. keeps reporting the same value."]
4105 FAILURE_TYPE_STUCK = 2,
4106 #[doc = "Unit is reporting complete garbage."]
4107 FAILURE_TYPE_GARBAGE = 3,
4108 #[doc = "Unit is consistently wrong."]
4109 FAILURE_TYPE_WRONG = 4,
4110 #[doc = "Unit is slow, so e.g. reporting at slower than expected rate."]
4111 FAILURE_TYPE_SLOW = 5,
4112 #[doc = "Data of unit is delayed in time."]
4113 FAILURE_TYPE_DELAYED = 6,
4114 #[doc = "Unit is sometimes working, sometimes not."]
4115 FAILURE_TYPE_INTERMITTENT = 7,
4116}
4117impl FailureType {
4118 pub const DEFAULT: Self = Self::FAILURE_TYPE_OK;
4119}
4120impl Default for FailureType {
4121 fn default() -> Self {
4122 Self::DEFAULT
4123 }
4124}
4125bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Gimbal device (low level) error flags (bitmap, 0 means no error)"] pub struct GimbalDeviceErrorFlags : u32 { # [doc = "Gimbal device is limited by hardware roll limit."] const GIMBAL_DEVICE_ERROR_FLAGS_AT_ROLL_LIMIT = 1 ; # [doc = "Gimbal device is limited by hardware pitch limit."] const GIMBAL_DEVICE_ERROR_FLAGS_AT_PITCH_LIMIT = 2 ; # [doc = "Gimbal device is limited by hardware yaw limit."] const GIMBAL_DEVICE_ERROR_FLAGS_AT_YAW_LIMIT = 4 ; # [doc = "There is an error with the gimbal encoders."] const GIMBAL_DEVICE_ERROR_FLAGS_ENCODER_ERROR = 8 ; # [doc = "There is an error with the gimbal power source."] const GIMBAL_DEVICE_ERROR_FLAGS_POWER_ERROR = 16 ; # [doc = "There is an error with the gimbal motors."] const GIMBAL_DEVICE_ERROR_FLAGS_MOTOR_ERROR = 32 ; # [doc = "There is an error with the gimbal's software."] const GIMBAL_DEVICE_ERROR_FLAGS_SOFTWARE_ERROR = 64 ; # [doc = "There is an error with the gimbal's communication."] const GIMBAL_DEVICE_ERROR_FLAGS_COMMS_ERROR = 128 ; # [doc = "Gimbal device is currently calibrating."] const GIMBAL_DEVICE_ERROR_FLAGS_CALIBRATION_RUNNING = 256 ; # [doc = "Gimbal device is not assigned to a gimbal manager."] const GIMBAL_DEVICE_ERROR_FLAGS_NO_MANAGER = 512 ; } }
4126impl GimbalDeviceErrorFlags {
4127 pub const DEFAULT: Self = Self::GIMBAL_DEVICE_ERROR_FLAGS_AT_ROLL_LIMIT;
4128}
4129impl Default for GimbalDeviceErrorFlags {
4130 fn default() -> Self {
4131 Self::DEFAULT
4132 }
4133}
4134#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4135#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4136#[cfg_attr(feature = "serde", serde(tag = "type"))]
4137#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4138#[repr(u32)]
4139#[doc = "Gripper actions."]
4140pub enum GripperActions {
4141 #[doc = "Gripper release cargo."]
4142 GRIPPER_ACTION_RELEASE = 0,
4143 #[doc = "Gripper grab onto cargo."]
4144 GRIPPER_ACTION_GRAB = 1,
4145}
4146impl GripperActions {
4147 pub const DEFAULT: Self = Self::GRIPPER_ACTION_RELEASE;
4148}
4149impl Default for GripperActions {
4150 fn default() -> Self {
4151 Self::DEFAULT
4152 }
4153}
4154#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4155#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4156#[cfg_attr(feature = "serde", serde(tag = "type"))]
4157#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4158#[repr(u32)]
4159#[doc = "Indicates the ESC connection type."]
4160pub enum EscConnectionType {
4161 #[doc = "Traditional PPM ESC."]
4162 ESC_CONNECTION_TYPE_PPM = 0,
4163 #[doc = "Serial Bus connected ESC."]
4164 ESC_CONNECTION_TYPE_SERIAL = 1,
4165 #[doc = "One Shot PPM ESC."]
4166 ESC_CONNECTION_TYPE_ONESHOT = 2,
4167 #[doc = "I2C ESC."]
4168 ESC_CONNECTION_TYPE_I2C = 3,
4169 #[doc = "CAN-Bus ESC."]
4170 ESC_CONNECTION_TYPE_CAN = 4,
4171 #[doc = "DShot ESC."]
4172 ESC_CONNECTION_TYPE_DSHOT = 5,
4173}
4174impl EscConnectionType {
4175 pub const DEFAULT: Self = Self::ESC_CONNECTION_TYPE_PPM;
4176}
4177impl Default for EscConnectionType {
4178 fn default() -> Self {
4179 Self::DEFAULT
4180 }
4181}
4182#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4183#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4184#[cfg_attr(feature = "serde", serde(tag = "type"))]
4185#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4186#[repr(u32)]
4187pub enum MavlinkDataStreamType {
4188 MAVLINK_DATA_STREAM_IMG_JPEG = 0,
4189 MAVLINK_DATA_STREAM_IMG_BMP = 1,
4190 MAVLINK_DATA_STREAM_IMG_RAW8U = 2,
4191 MAVLINK_DATA_STREAM_IMG_RAW32U = 3,
4192 MAVLINK_DATA_STREAM_IMG_PGM = 4,
4193 MAVLINK_DATA_STREAM_IMG_PNG = 5,
4194}
4195impl MavlinkDataStreamType {
4196 pub const DEFAULT: Self = Self::MAVLINK_DATA_STREAM_IMG_JPEG;
4197}
4198impl Default for MavlinkDataStreamType {
4199 fn default() -> Self {
4200 Self::DEFAULT
4201 }
4202}
4203bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Camera capability flags (Bitmap)"] pub struct CameraCapFlags : u32 { # [doc = "Camera is able to record video"] const CAMERA_CAP_FLAGS_CAPTURE_VIDEO = 1 ; # [doc = "Camera is able to capture images"] const CAMERA_CAP_FLAGS_CAPTURE_IMAGE = 2 ; # [doc = "Camera has separate Video and Image/Photo modes (MAV_CMD_SET_CAMERA_MODE)"] const CAMERA_CAP_FLAGS_HAS_MODES = 4 ; # [doc = "Camera can capture images while in video mode"] const CAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE = 8 ; # [doc = "Camera can capture videos while in Photo/Image mode"] const CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE = 16 ; # [doc = "Camera has image survey mode (MAV_CMD_SET_CAMERA_MODE)"] const CAMERA_CAP_FLAGS_HAS_IMAGE_SURVEY_MODE = 32 ; # [doc = "Camera has basic zoom control (MAV_CMD_SET_CAMERA_ZOOM)"] const CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM = 64 ; # [doc = "Camera has basic focus control (MAV_CMD_SET_CAMERA_FOCUS)"] const CAMERA_CAP_FLAGS_HAS_BASIC_FOCUS = 128 ; # [doc = "Camera has video streaming capabilities (request VIDEO_STREAM_INFORMATION with MAV_CMD_REQUEST_MESSAGE for video streaming info)"] const CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM = 256 ; # [doc = "Camera supports tracking of a point on the camera view."] const CAMERA_CAP_FLAGS_HAS_TRACKING_POINT = 512 ; # [doc = "Camera supports tracking of a selection rectangle on the camera view."] const CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE = 1024 ; # [doc = "Camera supports tracking geo status (CAMERA_TRACKING_GEO_STATUS)."] const CAMERA_CAP_FLAGS_HAS_TRACKING_GEO_STATUS = 2048 ; # [doc = "Camera supports absolute thermal range (request CAMERA_THERMAL_RANGE with MAV_CMD_REQUEST_MESSAGE)."] const CAMERA_CAP_FLAGS_HAS_THERMAL_RANGE = 4096 ; } }
4204impl CameraCapFlags {
4205 pub const DEFAULT: Self = Self::CAMERA_CAP_FLAGS_CAPTURE_VIDEO;
4206}
4207impl Default for CameraCapFlags {
4208 fn default() -> Self {
4209 Self::DEFAULT
4210 }
4211}
4212#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4213#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4214#[cfg_attr(feature = "serde", serde(tag = "type"))]
4215#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4216#[repr(u32)]
4217pub enum MavOdidIdType {
4218 #[doc = "No type defined."]
4219 MAV_ODID_ID_TYPE_NONE = 0,
4220 #[doc = "Manufacturer Serial Number (ANSI/CTA-2063 format)."]
4221 MAV_ODID_ID_TYPE_SERIAL_NUMBER = 1,
4222 #[doc = "CAA (Civil Aviation Authority) registered ID. Format: [ICAO Country Code].[CAA Assigned ID]."]
4223 MAV_ODID_ID_TYPE_CAA_REGISTRATION_ID = 2,
4224 #[doc = "UTM (Unmanned Traffic Management) assigned UUID (RFC4122)."]
4225 MAV_ODID_ID_TYPE_UTM_ASSIGNED_UUID = 3,
4226 #[doc = "A 20 byte ID for a specific flight/session. The exact ID type is indicated by the first byte of uas_id and these type values are managed by ICAO."]
4227 MAV_ODID_ID_TYPE_SPECIFIC_SESSION_ID = 4,
4228}
4229impl MavOdidIdType {
4230 pub const DEFAULT: Self = Self::MAV_ODID_ID_TYPE_NONE;
4231}
4232impl Default for MavOdidIdType {
4233 fn default() -> Self {
4234 Self::DEFAULT
4235 }
4236}
4237#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4238#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4239#[cfg_attr(feature = "serde", serde(tag = "type"))]
4240#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4241#[repr(u32)]
4242pub enum MavOdidUaType {
4243 #[doc = "No UA (Unmanned Aircraft) type defined."]
4244 MAV_ODID_UA_TYPE_NONE = 0,
4245 #[doc = "Aeroplane/Airplane. Fixed wing."]
4246 MAV_ODID_UA_TYPE_AEROPLANE = 1,
4247 #[doc = "Helicopter or multirotor."]
4248 MAV_ODID_UA_TYPE_HELICOPTER_OR_MULTIROTOR = 2,
4249 #[doc = "Gyroplane."]
4250 MAV_ODID_UA_TYPE_GYROPLANE = 3,
4251 #[doc = "VTOL (Vertical Take-Off and Landing). Fixed wing aircraft that can take off vertically."]
4252 MAV_ODID_UA_TYPE_HYBRID_LIFT = 4,
4253 #[doc = "Ornithopter."]
4254 MAV_ODID_UA_TYPE_ORNITHOPTER = 5,
4255 #[doc = "Glider."]
4256 MAV_ODID_UA_TYPE_GLIDER = 6,
4257 #[doc = "Kite."]
4258 MAV_ODID_UA_TYPE_KITE = 7,
4259 #[doc = "Free Balloon."]
4260 MAV_ODID_UA_TYPE_FREE_BALLOON = 8,
4261 #[doc = "Captive Balloon."]
4262 MAV_ODID_UA_TYPE_CAPTIVE_BALLOON = 9,
4263 #[doc = "Airship. E.g. a blimp."]
4264 MAV_ODID_UA_TYPE_AIRSHIP = 10,
4265 #[doc = "Free Fall/Parachute (unpowered)."]
4266 MAV_ODID_UA_TYPE_FREE_FALL_PARACHUTE = 11,
4267 #[doc = "Rocket."]
4268 MAV_ODID_UA_TYPE_ROCKET = 12,
4269 #[doc = "Tethered powered aircraft."]
4270 MAV_ODID_UA_TYPE_TETHERED_POWERED_AIRCRAFT = 13,
4271 #[doc = "Ground Obstacle."]
4272 MAV_ODID_UA_TYPE_GROUND_OBSTACLE = 14,
4273 #[doc = "Other type of aircraft not listed earlier."]
4274 MAV_ODID_UA_TYPE_OTHER = 15,
4275}
4276impl MavOdidUaType {
4277 pub const DEFAULT: Self = Self::MAV_ODID_UA_TYPE_NONE;
4278}
4279impl Default for MavOdidUaType {
4280 fn default() -> Self {
4281 Self::DEFAULT
4282 }
4283}
4284#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4285#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4286#[cfg_attr(feature = "serde", serde(tag = "type"))]
4287#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4288#[repr(u32)]
4289#[doc = "Direction of VTOL transition"]
4290pub enum VtolTransitionHeading {
4291 #[doc = "Respect the heading configuration of the vehicle."]
4292 VTOL_TRANSITION_HEADING_VEHICLE_DEFAULT = 0,
4293 #[doc = "Use the heading pointing towards the next waypoint."]
4294 VTOL_TRANSITION_HEADING_NEXT_WAYPOINT = 1,
4295 #[doc = "Use the heading on takeoff (while sitting on the ground)."]
4296 VTOL_TRANSITION_HEADING_TAKEOFF = 2,
4297 #[doc = "Use the specified heading in parameter 4."]
4298 VTOL_TRANSITION_HEADING_SPECIFIED = 3,
4299 #[doc = "Use the current heading when reaching takeoff altitude (potentially facing the wind when weather-vaning is active)."]
4300 VTOL_TRANSITION_HEADING_ANY = 4,
4301}
4302impl VtolTransitionHeading {
4303 pub const DEFAULT: Self = Self::VTOL_TRANSITION_HEADING_VEHICLE_DEFAULT;
4304}
4305impl Default for VtolTransitionHeading {
4306 fn default() -> Self {
4307 Self::DEFAULT
4308 }
4309}
4310#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4311#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4312#[cfg_attr(feature = "serde", serde(tag = "type"))]
4313#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4314#[repr(u32)]
4315#[doc = "Fence types to enable or disable when using MAV_CMD_DO_FENCE_ENABLE. Note that at least one of these flags must be set in MAV_CMD_DO_FENCE_ENABLE.param2. If none are set, the flight stack will ignore the field and enable/disable its default set of fences (usually all of them)."]
4316pub enum FenceType {
4317 #[doc = "Maximum altitude fence"]
4318 FENCE_TYPE_ALT_MAX = 1,
4319 #[doc = "Circle fence"]
4320 FENCE_TYPE_CIRCLE = 2,
4321 #[doc = "Polygon fence"]
4322 FENCE_TYPE_POLYGON = 4,
4323 #[doc = "Minimum altitude fence"]
4324 FENCE_TYPE_ALT_MIN = 8,
4325}
4326impl FenceType {
4327 pub const DEFAULT: Self = Self::FENCE_TYPE_ALT_MAX;
4328}
4329impl Default for FenceType {
4330 fn default() -> Self {
4331 Self::DEFAULT
4332 }
4333}
4334#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4335#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4336#[cfg_attr(feature = "serde", serde(tag = "type"))]
4337#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4338#[repr(u32)]
4339#[doc = "Camera tracking modes"]
4340pub enum CameraTrackingMode {
4341 #[doc = "Not tracking"]
4342 CAMERA_TRACKING_MODE_NONE = 0,
4343 #[doc = "Target is a point"]
4344 CAMERA_TRACKING_MODE_POINT = 1,
4345 #[doc = "Target is a rectangle"]
4346 CAMERA_TRACKING_MODE_RECTANGLE = 2,
4347}
4348impl CameraTrackingMode {
4349 pub const DEFAULT: Self = Self::CAMERA_TRACKING_MODE_NONE;
4350}
4351impl Default for CameraTrackingMode {
4352 fn default() -> Self {
4353 Self::DEFAULT
4354 }
4355}
4356#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4357#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4358#[cfg_attr(feature = "serde", serde(tag = "type"))]
4359#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4360#[repr(u32)]
4361#[doc = "Fuel types for use in FUEL_TYPE. Fuel types specify the units for the maximum, available and consumed fuel, and for the flow rates."]
4362pub enum MavFuelType {
4363 #[doc = "Not specified. Fuel levels are normalized (i.e. maximum is 1, and other levels are relative to 1)."]
4364 MAV_FUEL_TYPE_UNKNOWN = 0,
4365 #[doc = "A generic liquid fuel. Fuel levels are in millilitres (ml). Fuel rates are in millilitres/second."]
4366 MAV_FUEL_TYPE_LIQUID = 1,
4367 #[doc = "A gas tank. Fuel levels are in kilo-Pascal (kPa), and flow rates are in milliliters per second (ml/s)."]
4368 MAV_FUEL_TYPE_GAS = 2,
4369}
4370impl MavFuelType {
4371 pub const DEFAULT: Self = Self::MAV_FUEL_TYPE_UNKNOWN;
4372}
4373impl Default for MavFuelType {
4374 fn default() -> Self {
4375 Self::DEFAULT
4376 }
4377}
4378#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4379#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4380#[cfg_attr(feature = "serde", serde(tag = "type"))]
4381#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4382#[repr(u32)]
4383#[doc = "Sequence that motors are tested when using MAV_CMD_DO_MOTOR_TEST."]
4384pub enum MotorTestOrder {
4385 #[doc = "Default autopilot motor test method."]
4386 MOTOR_TEST_ORDER_DEFAULT = 0,
4387 #[doc = "Motor numbers are specified as their index in a predefined vehicle-specific sequence."]
4388 MOTOR_TEST_ORDER_SEQUENCE = 1,
4389 #[doc = "Motor numbers are specified as the output as labeled on the board."]
4390 MOTOR_TEST_ORDER_BOARD = 2,
4391}
4392impl MotorTestOrder {
4393 pub const DEFAULT: Self = Self::MOTOR_TEST_ORDER_DEFAULT;
4394}
4395impl Default for MotorTestOrder {
4396 fn default() -> Self {
4397 Self::DEFAULT
4398 }
4399}
4400#[doc = "id: 410"]
4401#[doc = "Event message. Each new event from a particular component gets a new sequence number. The same message might be sent multiple times if (re-)requested. Most events are broadcast, some can be specific to a target component (as receivers keep track of the sequence for missed events, all events need to be broadcast. Thus we use destination_component instead of target_component)."]
4402#[derive(Debug, Clone, PartialEq)]
4403#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4404#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4405pub struct EVENT_DATA {
4406 #[doc = "Event ID (as defined in the component metadata)"]
4407 pub id: u32,
4408 #[doc = "Timestamp (time since system boot when the event happened)."]
4409 pub event_time_boot_ms: u32,
4410 #[doc = "Sequence number."]
4411 pub sequence: u16,
4412 #[doc = "Component ID"]
4413 pub destination_component: u8,
4414 #[doc = "System ID"]
4415 pub destination_system: u8,
4416 #[doc = "Log levels: 4 bits MSB: internal (for logging purposes), 4 bits LSB: external. Levels: Emergency = 0, Alert = 1, Critical = 2, Error = 3, Warning = 4, Notice = 5, Info = 6, Debug = 7, Protocol = 8, Disabled = 9"]
4417 pub log_levels: u8,
4418 #[doc = "Arguments (depend on event ID)."]
4419 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
4420 pub arguments: [u8; 40],
4421}
4422impl EVENT_DATA {
4423 pub const ENCODED_LEN: usize = 53usize;
4424 pub const DEFAULT: Self = Self {
4425 id: 0_u32,
4426 event_time_boot_ms: 0_u32,
4427 sequence: 0_u16,
4428 destination_component: 0_u8,
4429 destination_system: 0_u8,
4430 log_levels: 0_u8,
4431 arguments: [0_u8; 40usize],
4432 };
4433 #[cfg(feature = "arbitrary")]
4434 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
4435 use arbitrary::{Arbitrary, Unstructured};
4436 let mut buf = [0u8; 1024];
4437 rng.fill_bytes(&mut buf);
4438 let mut unstructured = Unstructured::new(&buf);
4439 Self::arbitrary(&mut unstructured).unwrap_or_default()
4440 }
4441}
4442impl Default for EVENT_DATA {
4443 fn default() -> Self {
4444 Self::DEFAULT.clone()
4445 }
4446}
4447impl MessageData for EVENT_DATA {
4448 type Message = MavMessage;
4449 const ID: u32 = 410u32;
4450 const NAME: &'static str = "EVENT";
4451 const EXTRA_CRC: u8 = 160u8;
4452 const ENCODED_LEN: usize = 53usize;
4453 fn deser(
4454 _version: MavlinkVersion,
4455 __input: &[u8],
4456 ) -> Result<Self, ::mavlink_core::error::ParserError> {
4457 let avail_len = __input.len();
4458 let mut payload_buf = [0; Self::ENCODED_LEN];
4459 let mut buf = if avail_len < Self::ENCODED_LEN {
4460 payload_buf[0..avail_len].copy_from_slice(__input);
4461 Bytes::new(&payload_buf)
4462 } else {
4463 Bytes::new(__input)
4464 };
4465 let mut __struct = Self::default();
4466 __struct.id = buf.get_u32_le();
4467 __struct.event_time_boot_ms = buf.get_u32_le();
4468 __struct.sequence = buf.get_u16_le();
4469 __struct.destination_component = buf.get_u8();
4470 __struct.destination_system = buf.get_u8();
4471 __struct.log_levels = buf.get_u8();
4472 for v in &mut __struct.arguments {
4473 let val = buf.get_u8();
4474 *v = val;
4475 }
4476 Ok(__struct)
4477 }
4478 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
4479 let mut __tmp = BytesMut::new(bytes);
4480 #[allow(clippy::absurd_extreme_comparisons)]
4481 #[allow(unused_comparisons)]
4482 if __tmp.remaining() < Self::ENCODED_LEN {
4483 panic!(
4484 "buffer is too small (need {} bytes, but got {})",
4485 Self::ENCODED_LEN,
4486 __tmp.remaining(),
4487 )
4488 }
4489 __tmp.put_u32_le(self.id);
4490 __tmp.put_u32_le(self.event_time_boot_ms);
4491 __tmp.put_u16_le(self.sequence);
4492 __tmp.put_u8(self.destination_component);
4493 __tmp.put_u8(self.destination_system);
4494 __tmp.put_u8(self.log_levels);
4495 for val in &self.arguments {
4496 __tmp.put_u8(*val);
4497 }
4498 if matches!(version, MavlinkVersion::V2) {
4499 let len = __tmp.len();
4500 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
4501 } else {
4502 __tmp.len()
4503 }
4504 }
4505}
4506#[doc = "id: 300"]
4507#[doc = "Version and capability of protocol version. This message can be requested with MAV_CMD_REQUEST_MESSAGE and is used as part of the handshaking to establish which MAVLink version should be used on the network. Every node should respond to a request for PROTOCOL_VERSION to enable the handshaking. Library implementers should consider adding this into the default decoding state machine to allow the protocol core to respond directly."]
4508#[derive(Debug, Clone, PartialEq)]
4509#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4510#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4511pub struct PROTOCOL_VERSION_DATA {
4512 #[doc = "Currently active MAVLink version number * 100: v1.0 is 100, v2.0 is 200, etc."]
4513 pub version: u16,
4514 #[doc = "Minimum MAVLink version supported"]
4515 pub min_version: u16,
4516 #[doc = "Maximum MAVLink version supported (set to the same value as version by default)"]
4517 pub max_version: u16,
4518 #[doc = "The first 8 bytes (not characters printed in hex!) of the git hash."]
4519 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
4520 pub spec_version_hash: [u8; 8],
4521 #[doc = "The first 8 bytes (not characters printed in hex!) of the git hash."]
4522 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
4523 pub library_version_hash: [u8; 8],
4524}
4525impl PROTOCOL_VERSION_DATA {
4526 pub const ENCODED_LEN: usize = 22usize;
4527 pub const DEFAULT: Self = Self {
4528 version: 0_u16,
4529 min_version: 0_u16,
4530 max_version: 0_u16,
4531 spec_version_hash: [0_u8; 8usize],
4532 library_version_hash: [0_u8; 8usize],
4533 };
4534 #[cfg(feature = "arbitrary")]
4535 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
4536 use arbitrary::{Arbitrary, Unstructured};
4537 let mut buf = [0u8; 1024];
4538 rng.fill_bytes(&mut buf);
4539 let mut unstructured = Unstructured::new(&buf);
4540 Self::arbitrary(&mut unstructured).unwrap_or_default()
4541 }
4542}
4543impl Default for PROTOCOL_VERSION_DATA {
4544 fn default() -> Self {
4545 Self::DEFAULT.clone()
4546 }
4547}
4548impl MessageData for PROTOCOL_VERSION_DATA {
4549 type Message = MavMessage;
4550 const ID: u32 = 300u32;
4551 const NAME: &'static str = "PROTOCOL_VERSION";
4552 const EXTRA_CRC: u8 = 217u8;
4553 const ENCODED_LEN: usize = 22usize;
4554 fn deser(
4555 _version: MavlinkVersion,
4556 __input: &[u8],
4557 ) -> Result<Self, ::mavlink_core::error::ParserError> {
4558 let avail_len = __input.len();
4559 let mut payload_buf = [0; Self::ENCODED_LEN];
4560 let mut buf = if avail_len < Self::ENCODED_LEN {
4561 payload_buf[0..avail_len].copy_from_slice(__input);
4562 Bytes::new(&payload_buf)
4563 } else {
4564 Bytes::new(__input)
4565 };
4566 let mut __struct = Self::default();
4567 __struct.version = buf.get_u16_le();
4568 __struct.min_version = buf.get_u16_le();
4569 __struct.max_version = buf.get_u16_le();
4570 for v in &mut __struct.spec_version_hash {
4571 let val = buf.get_u8();
4572 *v = val;
4573 }
4574 for v in &mut __struct.library_version_hash {
4575 let val = buf.get_u8();
4576 *v = val;
4577 }
4578 Ok(__struct)
4579 }
4580 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
4581 let mut __tmp = BytesMut::new(bytes);
4582 #[allow(clippy::absurd_extreme_comparisons)]
4583 #[allow(unused_comparisons)]
4584 if __tmp.remaining() < Self::ENCODED_LEN {
4585 panic!(
4586 "buffer is too small (need {} bytes, but got {})",
4587 Self::ENCODED_LEN,
4588 __tmp.remaining(),
4589 )
4590 }
4591 __tmp.put_u16_le(self.version);
4592 __tmp.put_u16_le(self.min_version);
4593 __tmp.put_u16_le(self.max_version);
4594 for val in &self.spec_version_hash {
4595 __tmp.put_u8(*val);
4596 }
4597 for val in &self.library_version_hash {
4598 __tmp.put_u8(*val);
4599 }
4600 if matches!(version, MavlinkVersion::V2) {
4601 let len = __tmp.len();
4602 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
4603 } else {
4604 __tmp.len()
4605 }
4606 }
4607}
4608#[doc = "id: 22"]
4609#[doc = "Emit the value of a onboard parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows him to re-request missing parameters after a loss or timeout. The parameter microservice is documented at <https://mavlink.io/en/services/parameter.html>."]
4610#[derive(Debug, Clone, PartialEq)]
4611#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4612#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4613pub struct PARAM_VALUE_DATA {
4614 #[doc = "Onboard parameter value"]
4615 pub param_value: f32,
4616 #[doc = "Total number of onboard parameters"]
4617 pub param_count: u16,
4618 #[doc = "Index of this onboard parameter"]
4619 pub param_index: u16,
4620 #[doc = "Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string"]
4621 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
4622 pub param_id: [u8; 16],
4623 #[doc = "Onboard parameter type."]
4624 pub param_type: MavParamType,
4625}
4626impl PARAM_VALUE_DATA {
4627 pub const ENCODED_LEN: usize = 25usize;
4628 pub const DEFAULT: Self = Self {
4629 param_value: 0.0_f32,
4630 param_count: 0_u16,
4631 param_index: 0_u16,
4632 param_id: [0_u8; 16usize],
4633 param_type: MavParamType::DEFAULT,
4634 };
4635 #[cfg(feature = "arbitrary")]
4636 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
4637 use arbitrary::{Arbitrary, Unstructured};
4638 let mut buf = [0u8; 1024];
4639 rng.fill_bytes(&mut buf);
4640 let mut unstructured = Unstructured::new(&buf);
4641 Self::arbitrary(&mut unstructured).unwrap_or_default()
4642 }
4643}
4644impl Default for PARAM_VALUE_DATA {
4645 fn default() -> Self {
4646 Self::DEFAULT.clone()
4647 }
4648}
4649impl MessageData for PARAM_VALUE_DATA {
4650 type Message = MavMessage;
4651 const ID: u32 = 22u32;
4652 const NAME: &'static str = "PARAM_VALUE";
4653 const EXTRA_CRC: u8 = 220u8;
4654 const ENCODED_LEN: usize = 25usize;
4655 fn deser(
4656 _version: MavlinkVersion,
4657 __input: &[u8],
4658 ) -> Result<Self, ::mavlink_core::error::ParserError> {
4659 let avail_len = __input.len();
4660 let mut payload_buf = [0; Self::ENCODED_LEN];
4661 let mut buf = if avail_len < Self::ENCODED_LEN {
4662 payload_buf[0..avail_len].copy_from_slice(__input);
4663 Bytes::new(&payload_buf)
4664 } else {
4665 Bytes::new(__input)
4666 };
4667 let mut __struct = Self::default();
4668 __struct.param_value = buf.get_f32_le();
4669 __struct.param_count = buf.get_u16_le();
4670 __struct.param_index = buf.get_u16_le();
4671 for v in &mut __struct.param_id {
4672 let val = buf.get_u8();
4673 *v = val;
4674 }
4675 let tmp = buf.get_u8();
4676 __struct.param_type =
4677 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
4678 enum_type: "MavParamType",
4679 value: tmp as u32,
4680 })?;
4681 Ok(__struct)
4682 }
4683 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
4684 let mut __tmp = BytesMut::new(bytes);
4685 #[allow(clippy::absurd_extreme_comparisons)]
4686 #[allow(unused_comparisons)]
4687 if __tmp.remaining() < Self::ENCODED_LEN {
4688 panic!(
4689 "buffer is too small (need {} bytes, but got {})",
4690 Self::ENCODED_LEN,
4691 __tmp.remaining(),
4692 )
4693 }
4694 __tmp.put_f32_le(self.param_value);
4695 __tmp.put_u16_le(self.param_count);
4696 __tmp.put_u16_le(self.param_index);
4697 for val in &self.param_id {
4698 __tmp.put_u8(*val);
4699 }
4700 __tmp.put_u8(self.param_type as u8);
4701 if matches!(version, MavlinkVersion::V2) {
4702 let len = __tmp.len();
4703 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
4704 } else {
4705 __tmp.len()
4706 }
4707 }
4708}
4709#[doc = "id: 114"]
4710#[doc = "Simulated optical flow from a flow sensor (e.g. PX4FLOW or optical mouse sensor)."]
4711#[derive(Debug, Clone, PartialEq)]
4712#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4713#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4714pub struct HIL_OPTICAL_FLOW_DATA {
4715 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
4716 pub time_usec: u64,
4717 #[doc = "Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the."]
4718 pub integration_time_us: u32,
4719 #[doc = "Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)"]
4720 pub integrated_x: f32,
4721 #[doc = "Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)"]
4722 pub integrated_y: f32,
4723 #[doc = "RH rotation around X axis"]
4724 pub integrated_xgyro: f32,
4725 #[doc = "RH rotation around Y axis"]
4726 pub integrated_ygyro: f32,
4727 #[doc = "RH rotation around Z axis"]
4728 pub integrated_zgyro: f32,
4729 #[doc = "Time since the distance was sampled."]
4730 pub time_delta_distance_us: u32,
4731 #[doc = "Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance."]
4732 pub distance: f32,
4733 #[doc = "Temperature"]
4734 pub temperature: i16,
4735 #[doc = "Sensor ID"]
4736 pub sensor_id: u8,
4737 #[doc = "Optical flow quality / confidence. 0: no valid flow, 255: maximum quality"]
4738 pub quality: u8,
4739}
4740impl HIL_OPTICAL_FLOW_DATA {
4741 pub const ENCODED_LEN: usize = 44usize;
4742 pub const DEFAULT: Self = Self {
4743 time_usec: 0_u64,
4744 integration_time_us: 0_u32,
4745 integrated_x: 0.0_f32,
4746 integrated_y: 0.0_f32,
4747 integrated_xgyro: 0.0_f32,
4748 integrated_ygyro: 0.0_f32,
4749 integrated_zgyro: 0.0_f32,
4750 time_delta_distance_us: 0_u32,
4751 distance: 0.0_f32,
4752 temperature: 0_i16,
4753 sensor_id: 0_u8,
4754 quality: 0_u8,
4755 };
4756 #[cfg(feature = "arbitrary")]
4757 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
4758 use arbitrary::{Arbitrary, Unstructured};
4759 let mut buf = [0u8; 1024];
4760 rng.fill_bytes(&mut buf);
4761 let mut unstructured = Unstructured::new(&buf);
4762 Self::arbitrary(&mut unstructured).unwrap_or_default()
4763 }
4764}
4765impl Default for HIL_OPTICAL_FLOW_DATA {
4766 fn default() -> Self {
4767 Self::DEFAULT.clone()
4768 }
4769}
4770impl MessageData for HIL_OPTICAL_FLOW_DATA {
4771 type Message = MavMessage;
4772 const ID: u32 = 114u32;
4773 const NAME: &'static str = "HIL_OPTICAL_FLOW";
4774 const EXTRA_CRC: u8 = 237u8;
4775 const ENCODED_LEN: usize = 44usize;
4776 fn deser(
4777 _version: MavlinkVersion,
4778 __input: &[u8],
4779 ) -> Result<Self, ::mavlink_core::error::ParserError> {
4780 let avail_len = __input.len();
4781 let mut payload_buf = [0; Self::ENCODED_LEN];
4782 let mut buf = if avail_len < Self::ENCODED_LEN {
4783 payload_buf[0..avail_len].copy_from_slice(__input);
4784 Bytes::new(&payload_buf)
4785 } else {
4786 Bytes::new(__input)
4787 };
4788 let mut __struct = Self::default();
4789 __struct.time_usec = buf.get_u64_le();
4790 __struct.integration_time_us = buf.get_u32_le();
4791 __struct.integrated_x = buf.get_f32_le();
4792 __struct.integrated_y = buf.get_f32_le();
4793 __struct.integrated_xgyro = buf.get_f32_le();
4794 __struct.integrated_ygyro = buf.get_f32_le();
4795 __struct.integrated_zgyro = buf.get_f32_le();
4796 __struct.time_delta_distance_us = buf.get_u32_le();
4797 __struct.distance = buf.get_f32_le();
4798 __struct.temperature = buf.get_i16_le();
4799 __struct.sensor_id = buf.get_u8();
4800 __struct.quality = buf.get_u8();
4801 Ok(__struct)
4802 }
4803 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
4804 let mut __tmp = BytesMut::new(bytes);
4805 #[allow(clippy::absurd_extreme_comparisons)]
4806 #[allow(unused_comparisons)]
4807 if __tmp.remaining() < Self::ENCODED_LEN {
4808 panic!(
4809 "buffer is too small (need {} bytes, but got {})",
4810 Self::ENCODED_LEN,
4811 __tmp.remaining(),
4812 )
4813 }
4814 __tmp.put_u64_le(self.time_usec);
4815 __tmp.put_u32_le(self.integration_time_us);
4816 __tmp.put_f32_le(self.integrated_x);
4817 __tmp.put_f32_le(self.integrated_y);
4818 __tmp.put_f32_le(self.integrated_xgyro);
4819 __tmp.put_f32_le(self.integrated_ygyro);
4820 __tmp.put_f32_le(self.integrated_zgyro);
4821 __tmp.put_u32_le(self.time_delta_distance_us);
4822 __tmp.put_f32_le(self.distance);
4823 __tmp.put_i16_le(self.temperature);
4824 __tmp.put_u8(self.sensor_id);
4825 __tmp.put_u8(self.quality);
4826 if matches!(version, MavlinkVersion::V2) {
4827 let len = __tmp.len();
4828 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
4829 } else {
4830 __tmp.len()
4831 }
4832 }
4833}
4834#[doc = "id: 132"]
4835#[doc = "Distance sensor information for an onboard rangefinder."]
4836#[derive(Debug, Clone, PartialEq)]
4837#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4838#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4839pub struct DISTANCE_SENSOR_DATA {
4840 #[doc = "Timestamp (time since system boot)."]
4841 pub time_boot_ms: u32,
4842 #[doc = "Minimum distance the sensor can measure"]
4843 pub min_distance: u16,
4844 #[doc = "Maximum distance the sensor can measure"]
4845 pub max_distance: u16,
4846 #[doc = "Current distance reading"]
4847 pub current_distance: u16,
4848 #[doc = "Type of distance sensor."]
4849 pub mavtype: MavDistanceSensor,
4850 #[doc = "Onboard ID of the sensor"]
4851 pub id: u8,
4852 #[doc = "Direction the sensor faces. downward-facing: ROTATION_PITCH_270, upward-facing: ROTATION_PITCH_90, backward-facing: ROTATION_PITCH_180, forward-facing: ROTATION_NONE, left-facing: ROTATION_YAW_90, right-facing: ROTATION_YAW_270"]
4853 pub orientation: MavSensorOrientation,
4854 #[doc = "Measurement variance. Max standard deviation is 6cm. UINT8_MAX if unknown."]
4855 pub covariance: u8,
4856 #[doc = "Horizontal Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0."]
4857 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
4858 pub horizontal_fov: f32,
4859 #[doc = "Vertical Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0."]
4860 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
4861 pub vertical_fov: f32,
4862 #[doc = "Quaternion of the sensor orientation in vehicle body frame (w, x, y, z order, zero-rotation is 1, 0, 0, 0). Zero-rotation is along the vehicle body x-axis. This field is required if the orientation is set to MAV_SENSOR_ROTATION_CUSTOM. Set it to 0 if invalid.\""]
4863 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
4864 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
4865 pub quaternion: [f32; 4],
4866 #[doc = "Signal quality of the sensor. Specific to each sensor type, representing the relation of the signal strength with the target reflectivity, distance, size or aspect, but normalised as a percentage. 0 = unknown/unset signal quality, 1 = invalid signal, 100 = perfect signal."]
4867 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
4868 pub signal_quality: u8,
4869}
4870impl DISTANCE_SENSOR_DATA {
4871 pub const ENCODED_LEN: usize = 39usize;
4872 pub const DEFAULT: Self = Self {
4873 time_boot_ms: 0_u32,
4874 min_distance: 0_u16,
4875 max_distance: 0_u16,
4876 current_distance: 0_u16,
4877 mavtype: MavDistanceSensor::DEFAULT,
4878 id: 0_u8,
4879 orientation: MavSensorOrientation::DEFAULT,
4880 covariance: 0_u8,
4881 horizontal_fov: 0.0_f32,
4882 vertical_fov: 0.0_f32,
4883 quaternion: [0.0_f32; 4usize],
4884 signal_quality: 0_u8,
4885 };
4886 #[cfg(feature = "arbitrary")]
4887 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
4888 use arbitrary::{Arbitrary, Unstructured};
4889 let mut buf = [0u8; 1024];
4890 rng.fill_bytes(&mut buf);
4891 let mut unstructured = Unstructured::new(&buf);
4892 Self::arbitrary(&mut unstructured).unwrap_or_default()
4893 }
4894}
4895impl Default for DISTANCE_SENSOR_DATA {
4896 fn default() -> Self {
4897 Self::DEFAULT.clone()
4898 }
4899}
4900impl MessageData for DISTANCE_SENSOR_DATA {
4901 type Message = MavMessage;
4902 const ID: u32 = 132u32;
4903 const NAME: &'static str = "DISTANCE_SENSOR";
4904 const EXTRA_CRC: u8 = 85u8;
4905 const ENCODED_LEN: usize = 39usize;
4906 fn deser(
4907 _version: MavlinkVersion,
4908 __input: &[u8],
4909 ) -> Result<Self, ::mavlink_core::error::ParserError> {
4910 let avail_len = __input.len();
4911 let mut payload_buf = [0; Self::ENCODED_LEN];
4912 let mut buf = if avail_len < Self::ENCODED_LEN {
4913 payload_buf[0..avail_len].copy_from_slice(__input);
4914 Bytes::new(&payload_buf)
4915 } else {
4916 Bytes::new(__input)
4917 };
4918 let mut __struct = Self::default();
4919 __struct.time_boot_ms = buf.get_u32_le();
4920 __struct.min_distance = buf.get_u16_le();
4921 __struct.max_distance = buf.get_u16_le();
4922 __struct.current_distance = buf.get_u16_le();
4923 let tmp = buf.get_u8();
4924 __struct.mavtype =
4925 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
4926 enum_type: "MavDistanceSensor",
4927 value: tmp as u32,
4928 })?;
4929 __struct.id = buf.get_u8();
4930 let tmp = buf.get_u8();
4931 __struct.orientation =
4932 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
4933 enum_type: "MavSensorOrientation",
4934 value: tmp as u32,
4935 })?;
4936 __struct.covariance = buf.get_u8();
4937 __struct.horizontal_fov = buf.get_f32_le();
4938 __struct.vertical_fov = buf.get_f32_le();
4939 for v in &mut __struct.quaternion {
4940 let val = buf.get_f32_le();
4941 *v = val;
4942 }
4943 __struct.signal_quality = buf.get_u8();
4944 Ok(__struct)
4945 }
4946 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
4947 let mut __tmp = BytesMut::new(bytes);
4948 #[allow(clippy::absurd_extreme_comparisons)]
4949 #[allow(unused_comparisons)]
4950 if __tmp.remaining() < Self::ENCODED_LEN {
4951 panic!(
4952 "buffer is too small (need {} bytes, but got {})",
4953 Self::ENCODED_LEN,
4954 __tmp.remaining(),
4955 )
4956 }
4957 __tmp.put_u32_le(self.time_boot_ms);
4958 __tmp.put_u16_le(self.min_distance);
4959 __tmp.put_u16_le(self.max_distance);
4960 __tmp.put_u16_le(self.current_distance);
4961 __tmp.put_u8(self.mavtype as u8);
4962 __tmp.put_u8(self.id);
4963 __tmp.put_u8(self.orientation as u8);
4964 __tmp.put_u8(self.covariance);
4965 __tmp.put_f32_le(self.horizontal_fov);
4966 __tmp.put_f32_le(self.vertical_fov);
4967 for val in &self.quaternion {
4968 __tmp.put_f32_le(*val);
4969 }
4970 __tmp.put_u8(self.signal_quality);
4971 if matches!(version, MavlinkVersion::V2) {
4972 let len = __tmp.len();
4973 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
4974 } else {
4975 __tmp.len()
4976 }
4977 }
4978}
4979#[doc = "id: 232"]
4980#[doc = "GPS sensor input message. This is a raw sensor value sent by the GPS. This is NOT the global position estimate of the system."]
4981#[derive(Debug, Clone, PartialEq)]
4982#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4983#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4984pub struct GPS_INPUT_DATA {
4985 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
4986 pub time_usec: u64,
4987 #[doc = "GPS time (from start of GPS week)"]
4988 pub time_week_ms: u32,
4989 #[doc = "Latitude (WGS84)"]
4990 pub lat: i32,
4991 #[doc = "Longitude (WGS84)"]
4992 pub lon: i32,
4993 #[doc = "Altitude (MSL). Positive for up."]
4994 pub alt: f32,
4995 #[doc = "GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX"]
4996 pub hdop: f32,
4997 #[doc = "GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX"]
4998 pub vdop: f32,
4999 #[doc = "GPS velocity in north direction in earth-fixed NED frame"]
5000 pub vn: f32,
5001 #[doc = "GPS velocity in east direction in earth-fixed NED frame"]
5002 pub ve: f32,
5003 #[doc = "GPS velocity in down direction in earth-fixed NED frame"]
5004 pub vd: f32,
5005 #[doc = "GPS speed accuracy"]
5006 pub speed_accuracy: f32,
5007 #[doc = "GPS horizontal accuracy"]
5008 pub horiz_accuracy: f32,
5009 #[doc = "GPS vertical accuracy"]
5010 pub vert_accuracy: f32,
5011 #[doc = "Bitmap indicating which GPS input flags fields to ignore. All other fields must be provided."]
5012 pub ignore_flags: GpsInputIgnoreFlags,
5013 #[doc = "GPS week number"]
5014 pub time_week: u16,
5015 #[doc = "ID of the GPS for multiple GPS inputs"]
5016 pub gps_id: u8,
5017 #[doc = "0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK"]
5018 pub fix_type: u8,
5019 #[doc = "Number of satellites visible."]
5020 pub satellites_visible: u8,
5021 #[doc = "Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north"]
5022 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
5023 pub yaw: u16,
5024}
5025impl GPS_INPUT_DATA {
5026 pub const ENCODED_LEN: usize = 65usize;
5027 pub const DEFAULT: Self = Self {
5028 time_usec: 0_u64,
5029 time_week_ms: 0_u32,
5030 lat: 0_i32,
5031 lon: 0_i32,
5032 alt: 0.0_f32,
5033 hdop: 0.0_f32,
5034 vdop: 0.0_f32,
5035 vn: 0.0_f32,
5036 ve: 0.0_f32,
5037 vd: 0.0_f32,
5038 speed_accuracy: 0.0_f32,
5039 horiz_accuracy: 0.0_f32,
5040 vert_accuracy: 0.0_f32,
5041 ignore_flags: GpsInputIgnoreFlags::DEFAULT,
5042 time_week: 0_u16,
5043 gps_id: 0_u8,
5044 fix_type: 0_u8,
5045 satellites_visible: 0_u8,
5046 yaw: 0_u16,
5047 };
5048 #[cfg(feature = "arbitrary")]
5049 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
5050 use arbitrary::{Arbitrary, Unstructured};
5051 let mut buf = [0u8; 1024];
5052 rng.fill_bytes(&mut buf);
5053 let mut unstructured = Unstructured::new(&buf);
5054 Self::arbitrary(&mut unstructured).unwrap_or_default()
5055 }
5056}
5057impl Default for GPS_INPUT_DATA {
5058 fn default() -> Self {
5059 Self::DEFAULT.clone()
5060 }
5061}
5062impl MessageData for GPS_INPUT_DATA {
5063 type Message = MavMessage;
5064 const ID: u32 = 232u32;
5065 const NAME: &'static str = "GPS_INPUT";
5066 const EXTRA_CRC: u8 = 151u8;
5067 const ENCODED_LEN: usize = 65usize;
5068 fn deser(
5069 _version: MavlinkVersion,
5070 __input: &[u8],
5071 ) -> Result<Self, ::mavlink_core::error::ParserError> {
5072 let avail_len = __input.len();
5073 let mut payload_buf = [0; Self::ENCODED_LEN];
5074 let mut buf = if avail_len < Self::ENCODED_LEN {
5075 payload_buf[0..avail_len].copy_from_slice(__input);
5076 Bytes::new(&payload_buf)
5077 } else {
5078 Bytes::new(__input)
5079 };
5080 let mut __struct = Self::default();
5081 __struct.time_usec = buf.get_u64_le();
5082 __struct.time_week_ms = buf.get_u32_le();
5083 __struct.lat = buf.get_i32_le();
5084 __struct.lon = buf.get_i32_le();
5085 __struct.alt = buf.get_f32_le();
5086 __struct.hdop = buf.get_f32_le();
5087 __struct.vdop = buf.get_f32_le();
5088 __struct.vn = buf.get_f32_le();
5089 __struct.ve = buf.get_f32_le();
5090 __struct.vd = buf.get_f32_le();
5091 __struct.speed_accuracy = buf.get_f32_le();
5092 __struct.horiz_accuracy = buf.get_f32_le();
5093 __struct.vert_accuracy = buf.get_f32_le();
5094 let tmp = buf.get_u16_le();
5095 __struct.ignore_flags = GpsInputIgnoreFlags::from_bits(
5096 tmp & GpsInputIgnoreFlags::all().bits(),
5097 )
5098 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
5099 flag_type: "GpsInputIgnoreFlags",
5100 value: tmp as u32,
5101 })?;
5102 __struct.time_week = buf.get_u16_le();
5103 __struct.gps_id = buf.get_u8();
5104 __struct.fix_type = buf.get_u8();
5105 __struct.satellites_visible = buf.get_u8();
5106 __struct.yaw = buf.get_u16_le();
5107 Ok(__struct)
5108 }
5109 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
5110 let mut __tmp = BytesMut::new(bytes);
5111 #[allow(clippy::absurd_extreme_comparisons)]
5112 #[allow(unused_comparisons)]
5113 if __tmp.remaining() < Self::ENCODED_LEN {
5114 panic!(
5115 "buffer is too small (need {} bytes, but got {})",
5116 Self::ENCODED_LEN,
5117 __tmp.remaining(),
5118 )
5119 }
5120 __tmp.put_u64_le(self.time_usec);
5121 __tmp.put_u32_le(self.time_week_ms);
5122 __tmp.put_i32_le(self.lat);
5123 __tmp.put_i32_le(self.lon);
5124 __tmp.put_f32_le(self.alt);
5125 __tmp.put_f32_le(self.hdop);
5126 __tmp.put_f32_le(self.vdop);
5127 __tmp.put_f32_le(self.vn);
5128 __tmp.put_f32_le(self.ve);
5129 __tmp.put_f32_le(self.vd);
5130 __tmp.put_f32_le(self.speed_accuracy);
5131 __tmp.put_f32_le(self.horiz_accuracy);
5132 __tmp.put_f32_le(self.vert_accuracy);
5133 __tmp.put_u16_le(self.ignore_flags.bits());
5134 __tmp.put_u16_le(self.time_week);
5135 __tmp.put_u8(self.gps_id);
5136 __tmp.put_u8(self.fix_type);
5137 __tmp.put_u8(self.satellites_visible);
5138 __tmp.put_u16_le(self.yaw);
5139 if matches!(version, MavlinkVersion::V2) {
5140 let len = __tmp.len();
5141 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
5142 } else {
5143 __tmp.len()
5144 }
5145 }
5146}
5147#[doc = "id: 259"]
5148#[doc = "Information about a camera. Can be requested with a MAV_CMD_REQUEST_MESSAGE command."]
5149#[derive(Debug, Clone, PartialEq)]
5150#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5151#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5152pub struct CAMERA_INFORMATION_DATA {
5153 #[doc = "Timestamp (time since system boot)."]
5154 pub time_boot_ms: u32,
5155 #[doc = "0xff). Use 0 if not known."]
5156 pub firmware_version: u32,
5157 #[doc = "Focal length. Use NaN if not known."]
5158 pub focal_length: f32,
5159 #[doc = "Image sensor size horizontal. Use NaN if not known."]
5160 pub sensor_size_h: f32,
5161 #[doc = "Image sensor size vertical. Use NaN if not known."]
5162 pub sensor_size_v: f32,
5163 #[doc = "Bitmap of camera capability flags."]
5164 pub flags: CameraCapFlags,
5165 #[doc = "Horizontal image resolution. Use 0 if not known."]
5166 pub resolution_h: u16,
5167 #[doc = "Vertical image resolution. Use 0 if not known."]
5168 pub resolution_v: u16,
5169 #[doc = "Camera definition version (iteration). Use 0 if not known."]
5170 pub cam_definition_version: u16,
5171 #[doc = "Name of the camera vendor"]
5172 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5173 pub vendor_name: [u8; 32],
5174 #[doc = "Name of the camera model"]
5175 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5176 pub model_name: [u8; 32],
5177 #[doc = "Reserved for a lens ID. Use 0 if not known."]
5178 pub lens_id: u8,
5179 #[doc = "Camera definition URI (if any, otherwise only basic functions will be available). HTTP- (http://) and MAVLink FTP- (mavlinkftp://) formatted URIs are allowed (and both must be supported by any GCS that implements the Camera Protocol). The definition file may be xz compressed, which will be indicated by the file extension .xml.xz (a GCS that implements the protocol must support decompressing the file). The string needs to be zero terminated. Use a zero-length string if not known."]
5180 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5181 pub cam_definition_uri: [u8; 140],
5182 #[doc = "Gimbal id of a gimbal associated with this camera. This is the component id of the gimbal device, or 1-6 for non mavlink gimbals. Use 0 if no gimbal is associated with the camera."]
5183 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
5184 pub gimbal_device_id: u8,
5185 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
5186 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
5187 pub camera_device_id: u8,
5188}
5189impl CAMERA_INFORMATION_DATA {
5190 pub const ENCODED_LEN: usize = 237usize;
5191 pub const DEFAULT: Self = Self {
5192 time_boot_ms: 0_u32,
5193 firmware_version: 0_u32,
5194 focal_length: 0.0_f32,
5195 sensor_size_h: 0.0_f32,
5196 sensor_size_v: 0.0_f32,
5197 flags: CameraCapFlags::DEFAULT,
5198 resolution_h: 0_u16,
5199 resolution_v: 0_u16,
5200 cam_definition_version: 0_u16,
5201 vendor_name: [0_u8; 32usize],
5202 model_name: [0_u8; 32usize],
5203 lens_id: 0_u8,
5204 cam_definition_uri: [0_u8; 140usize],
5205 gimbal_device_id: 0_u8,
5206 camera_device_id: 0_u8,
5207 };
5208 #[cfg(feature = "arbitrary")]
5209 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
5210 use arbitrary::{Arbitrary, Unstructured};
5211 let mut buf = [0u8; 1024];
5212 rng.fill_bytes(&mut buf);
5213 let mut unstructured = Unstructured::new(&buf);
5214 Self::arbitrary(&mut unstructured).unwrap_or_default()
5215 }
5216}
5217impl Default for CAMERA_INFORMATION_DATA {
5218 fn default() -> Self {
5219 Self::DEFAULT.clone()
5220 }
5221}
5222impl MessageData for CAMERA_INFORMATION_DATA {
5223 type Message = MavMessage;
5224 const ID: u32 = 259u32;
5225 const NAME: &'static str = "CAMERA_INFORMATION";
5226 const EXTRA_CRC: u8 = 92u8;
5227 const ENCODED_LEN: usize = 237usize;
5228 fn deser(
5229 _version: MavlinkVersion,
5230 __input: &[u8],
5231 ) -> Result<Self, ::mavlink_core::error::ParserError> {
5232 let avail_len = __input.len();
5233 let mut payload_buf = [0; Self::ENCODED_LEN];
5234 let mut buf = if avail_len < Self::ENCODED_LEN {
5235 payload_buf[0..avail_len].copy_from_slice(__input);
5236 Bytes::new(&payload_buf)
5237 } else {
5238 Bytes::new(__input)
5239 };
5240 let mut __struct = Self::default();
5241 __struct.time_boot_ms = buf.get_u32_le();
5242 __struct.firmware_version = buf.get_u32_le();
5243 __struct.focal_length = buf.get_f32_le();
5244 __struct.sensor_size_h = buf.get_f32_le();
5245 __struct.sensor_size_v = buf.get_f32_le();
5246 let tmp = buf.get_u32_le();
5247 __struct.flags = CameraCapFlags::from_bits(tmp & CameraCapFlags::all().bits()).ok_or(
5248 ::mavlink_core::error::ParserError::InvalidFlag {
5249 flag_type: "CameraCapFlags",
5250 value: tmp as u32,
5251 },
5252 )?;
5253 __struct.resolution_h = buf.get_u16_le();
5254 __struct.resolution_v = buf.get_u16_le();
5255 __struct.cam_definition_version = buf.get_u16_le();
5256 for v in &mut __struct.vendor_name {
5257 let val = buf.get_u8();
5258 *v = val;
5259 }
5260 for v in &mut __struct.model_name {
5261 let val = buf.get_u8();
5262 *v = val;
5263 }
5264 __struct.lens_id = buf.get_u8();
5265 for v in &mut __struct.cam_definition_uri {
5266 let val = buf.get_u8();
5267 *v = val;
5268 }
5269 __struct.gimbal_device_id = buf.get_u8();
5270 __struct.camera_device_id = buf.get_u8();
5271 Ok(__struct)
5272 }
5273 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
5274 let mut __tmp = BytesMut::new(bytes);
5275 #[allow(clippy::absurd_extreme_comparisons)]
5276 #[allow(unused_comparisons)]
5277 if __tmp.remaining() < Self::ENCODED_LEN {
5278 panic!(
5279 "buffer is too small (need {} bytes, but got {})",
5280 Self::ENCODED_LEN,
5281 __tmp.remaining(),
5282 )
5283 }
5284 __tmp.put_u32_le(self.time_boot_ms);
5285 __tmp.put_u32_le(self.firmware_version);
5286 __tmp.put_f32_le(self.focal_length);
5287 __tmp.put_f32_le(self.sensor_size_h);
5288 __tmp.put_f32_le(self.sensor_size_v);
5289 __tmp.put_u32_le(self.flags.bits());
5290 __tmp.put_u16_le(self.resolution_h);
5291 __tmp.put_u16_le(self.resolution_v);
5292 __tmp.put_u16_le(self.cam_definition_version);
5293 for val in &self.vendor_name {
5294 __tmp.put_u8(*val);
5295 }
5296 for val in &self.model_name {
5297 __tmp.put_u8(*val);
5298 }
5299 __tmp.put_u8(self.lens_id);
5300 for val in &self.cam_definition_uri {
5301 __tmp.put_u8(*val);
5302 }
5303 __tmp.put_u8(self.gimbal_device_id);
5304 __tmp.put_u8(self.camera_device_id);
5305 if matches!(version, MavlinkVersion::V2) {
5306 let len = __tmp.len();
5307 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
5308 } else {
5309 __tmp.len()
5310 }
5311 }
5312}
5313#[doc = "id: 283"]
5314#[doc = "Information about a low level gimbal. This message should be requested by the gimbal manager or a ground station using MAV_CMD_REQUEST_MESSAGE. The maximum angles and rates are the limits by hardware. However, the limits by software used are likely different/smaller and dependent on mode/settings/etc.."]
5315#[derive(Debug, Clone, PartialEq)]
5316#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5317#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5318pub struct GIMBAL_DEVICE_INFORMATION_DATA {
5319 #[doc = "UID of gimbal hardware (0 if unknown)."]
5320 pub uid: u64,
5321 #[doc = "Timestamp (time since system boot)."]
5322 pub time_boot_ms: u32,
5323 #[doc = "0xff)."]
5324 pub firmware_version: u32,
5325 #[doc = "0xff)."]
5326 pub hardware_version: u32,
5327 #[doc = "Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown."]
5328 pub roll_min: f32,
5329 #[doc = "Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown."]
5330 pub roll_max: f32,
5331 #[doc = "Minimum hardware pitch angle (positive: up, negative: down). NAN if unknown."]
5332 pub pitch_min: f32,
5333 #[doc = "Maximum hardware pitch angle (positive: up, negative: down). NAN if unknown."]
5334 pub pitch_max: f32,
5335 #[doc = "Minimum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown."]
5336 pub yaw_min: f32,
5337 #[doc = "Maximum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown."]
5338 pub yaw_max: f32,
5339 #[doc = "Bitmap of gimbal capability flags."]
5340 pub cap_flags: GimbalDeviceCapFlags,
5341 #[doc = "Bitmap for use for gimbal-specific capability flags."]
5342 pub custom_cap_flags: u16,
5343 #[doc = "Name of the gimbal vendor."]
5344 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5345 pub vendor_name: [u8; 32],
5346 #[doc = "Name of the gimbal model."]
5347 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5348 pub model_name: [u8; 32],
5349 #[doc = "Custom name of the gimbal given to it by the user."]
5350 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5351 pub custom_name: [u8; 32],
5352 #[doc = "This field is to be used if the gimbal manager and the gimbal device are the same component and hence have the same component ID. This field is then set to a number between 1-6. If the component ID is separate, this field is not required and must be set to 0."]
5353 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
5354 pub gimbal_device_id: u8,
5355}
5356impl GIMBAL_DEVICE_INFORMATION_DATA {
5357 pub const ENCODED_LEN: usize = 145usize;
5358 pub const DEFAULT: Self = Self {
5359 uid: 0_u64,
5360 time_boot_ms: 0_u32,
5361 firmware_version: 0_u32,
5362 hardware_version: 0_u32,
5363 roll_min: 0.0_f32,
5364 roll_max: 0.0_f32,
5365 pitch_min: 0.0_f32,
5366 pitch_max: 0.0_f32,
5367 yaw_min: 0.0_f32,
5368 yaw_max: 0.0_f32,
5369 cap_flags: GimbalDeviceCapFlags::DEFAULT,
5370 custom_cap_flags: 0_u16,
5371 vendor_name: [0_u8; 32usize],
5372 model_name: [0_u8; 32usize],
5373 custom_name: [0_u8; 32usize],
5374 gimbal_device_id: 0_u8,
5375 };
5376 #[cfg(feature = "arbitrary")]
5377 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
5378 use arbitrary::{Arbitrary, Unstructured};
5379 let mut buf = [0u8; 1024];
5380 rng.fill_bytes(&mut buf);
5381 let mut unstructured = Unstructured::new(&buf);
5382 Self::arbitrary(&mut unstructured).unwrap_or_default()
5383 }
5384}
5385impl Default for GIMBAL_DEVICE_INFORMATION_DATA {
5386 fn default() -> Self {
5387 Self::DEFAULT.clone()
5388 }
5389}
5390impl MessageData for GIMBAL_DEVICE_INFORMATION_DATA {
5391 type Message = MavMessage;
5392 const ID: u32 = 283u32;
5393 const NAME: &'static str = "GIMBAL_DEVICE_INFORMATION";
5394 const EXTRA_CRC: u8 = 74u8;
5395 const ENCODED_LEN: usize = 145usize;
5396 fn deser(
5397 _version: MavlinkVersion,
5398 __input: &[u8],
5399 ) -> Result<Self, ::mavlink_core::error::ParserError> {
5400 let avail_len = __input.len();
5401 let mut payload_buf = [0; Self::ENCODED_LEN];
5402 let mut buf = if avail_len < Self::ENCODED_LEN {
5403 payload_buf[0..avail_len].copy_from_slice(__input);
5404 Bytes::new(&payload_buf)
5405 } else {
5406 Bytes::new(__input)
5407 };
5408 let mut __struct = Self::default();
5409 __struct.uid = buf.get_u64_le();
5410 __struct.time_boot_ms = buf.get_u32_le();
5411 __struct.firmware_version = buf.get_u32_le();
5412 __struct.hardware_version = buf.get_u32_le();
5413 __struct.roll_min = buf.get_f32_le();
5414 __struct.roll_max = buf.get_f32_le();
5415 __struct.pitch_min = buf.get_f32_le();
5416 __struct.pitch_max = buf.get_f32_le();
5417 __struct.yaw_min = buf.get_f32_le();
5418 __struct.yaw_max = buf.get_f32_le();
5419 let tmp = buf.get_u16_le();
5420 __struct.cap_flags = GimbalDeviceCapFlags::from_bits(
5421 tmp & GimbalDeviceCapFlags::all().bits(),
5422 )
5423 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
5424 flag_type: "GimbalDeviceCapFlags",
5425 value: tmp as u32,
5426 })?;
5427 __struct.custom_cap_flags = buf.get_u16_le();
5428 for v in &mut __struct.vendor_name {
5429 let val = buf.get_u8();
5430 *v = val;
5431 }
5432 for v in &mut __struct.model_name {
5433 let val = buf.get_u8();
5434 *v = val;
5435 }
5436 for v in &mut __struct.custom_name {
5437 let val = buf.get_u8();
5438 *v = val;
5439 }
5440 __struct.gimbal_device_id = buf.get_u8();
5441 Ok(__struct)
5442 }
5443 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
5444 let mut __tmp = BytesMut::new(bytes);
5445 #[allow(clippy::absurd_extreme_comparisons)]
5446 #[allow(unused_comparisons)]
5447 if __tmp.remaining() < Self::ENCODED_LEN {
5448 panic!(
5449 "buffer is too small (need {} bytes, but got {})",
5450 Self::ENCODED_LEN,
5451 __tmp.remaining(),
5452 )
5453 }
5454 __tmp.put_u64_le(self.uid);
5455 __tmp.put_u32_le(self.time_boot_ms);
5456 __tmp.put_u32_le(self.firmware_version);
5457 __tmp.put_u32_le(self.hardware_version);
5458 __tmp.put_f32_le(self.roll_min);
5459 __tmp.put_f32_le(self.roll_max);
5460 __tmp.put_f32_le(self.pitch_min);
5461 __tmp.put_f32_le(self.pitch_max);
5462 __tmp.put_f32_le(self.yaw_min);
5463 __tmp.put_f32_le(self.yaw_max);
5464 __tmp.put_u16_le(self.cap_flags.bits());
5465 __tmp.put_u16_le(self.custom_cap_flags);
5466 for val in &self.vendor_name {
5467 __tmp.put_u8(*val);
5468 }
5469 for val in &self.model_name {
5470 __tmp.put_u8(*val);
5471 }
5472 for val in &self.custom_name {
5473 __tmp.put_u8(*val);
5474 }
5475 __tmp.put_u8(self.gimbal_device_id);
5476 if matches!(version, MavlinkVersion::V2) {
5477 let len = __tmp.len();
5478 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
5479 } else {
5480 __tmp.len()
5481 }
5482 }
5483}
5484#[doc = "id: 2"]
5485#[doc = "The system time is the time of the master clock. This can be emitted by flight controllers, onboard computers, or other components in the MAVLink network. Components that are using a less reliable time source, such as a battery-backed real time clock, can choose to match their system clock to that of a SYSTEM_TYPE that indicates a more recent time. This allows more broadly accurate date stamping of logs, and so on. If precise time synchronization is needed then use TIMESYNC instead."]
5486#[derive(Debug, Clone, PartialEq)]
5487#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5488#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5489pub struct SYSTEM_TIME_DATA {
5490 #[doc = "Timestamp (UNIX epoch time)."]
5491 pub time_unix_usec: u64,
5492 #[doc = "Timestamp (time since system boot)."]
5493 pub time_boot_ms: u32,
5494}
5495impl SYSTEM_TIME_DATA {
5496 pub const ENCODED_LEN: usize = 12usize;
5497 pub const DEFAULT: Self = Self {
5498 time_unix_usec: 0_u64,
5499 time_boot_ms: 0_u32,
5500 };
5501 #[cfg(feature = "arbitrary")]
5502 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
5503 use arbitrary::{Arbitrary, Unstructured};
5504 let mut buf = [0u8; 1024];
5505 rng.fill_bytes(&mut buf);
5506 let mut unstructured = Unstructured::new(&buf);
5507 Self::arbitrary(&mut unstructured).unwrap_or_default()
5508 }
5509}
5510impl Default for SYSTEM_TIME_DATA {
5511 fn default() -> Self {
5512 Self::DEFAULT.clone()
5513 }
5514}
5515impl MessageData for SYSTEM_TIME_DATA {
5516 type Message = MavMessage;
5517 const ID: u32 = 2u32;
5518 const NAME: &'static str = "SYSTEM_TIME";
5519 const EXTRA_CRC: u8 = 137u8;
5520 const ENCODED_LEN: usize = 12usize;
5521 fn deser(
5522 _version: MavlinkVersion,
5523 __input: &[u8],
5524 ) -> Result<Self, ::mavlink_core::error::ParserError> {
5525 let avail_len = __input.len();
5526 let mut payload_buf = [0; Self::ENCODED_LEN];
5527 let mut buf = if avail_len < Self::ENCODED_LEN {
5528 payload_buf[0..avail_len].copy_from_slice(__input);
5529 Bytes::new(&payload_buf)
5530 } else {
5531 Bytes::new(__input)
5532 };
5533 let mut __struct = Self::default();
5534 __struct.time_unix_usec = buf.get_u64_le();
5535 __struct.time_boot_ms = buf.get_u32_le();
5536 Ok(__struct)
5537 }
5538 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
5539 let mut __tmp = BytesMut::new(bytes);
5540 #[allow(clippy::absurd_extreme_comparisons)]
5541 #[allow(unused_comparisons)]
5542 if __tmp.remaining() < Self::ENCODED_LEN {
5543 panic!(
5544 "buffer is too small (need {} bytes, but got {})",
5545 Self::ENCODED_LEN,
5546 __tmp.remaining(),
5547 )
5548 }
5549 __tmp.put_u64_le(self.time_unix_usec);
5550 __tmp.put_u32_le(self.time_boot_ms);
5551 if matches!(version, MavlinkVersion::V2) {
5552 let len = __tmp.len();
5553 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
5554 } else {
5555 __tmp.len()
5556 }
5557 }
5558}
5559#[doc = "id: 243"]
5560#[doc = "Sets the home position. \tThe home position is the default position that the system will return to and land on. The position is set automatically by the system during the takeoff (and may also be set using this message). The global and local positions encode the position in the respective coordinate frames, while the q parameter encodes the orientation of the surface. Under normal conditions it describes the heading and terrain slope, which can be used by the aircraft to adjust the approach. The approach 3D vector describes the point to which the system should fly in normal flight mode and then perform a landing sequence along the vector. Note: the current home position may be emitted in a HOME_POSITION message on request (using MAV_CMD_REQUEST_MESSAGE with param1=242)."]
5561#[derive(Debug, Clone, PartialEq)]
5562#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5563#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5564pub struct SET_HOME_POSITION_DATA {
5565 #[doc = "Latitude (WGS84)"]
5566 pub latitude: i32,
5567 #[doc = "Longitude (WGS84)"]
5568 pub longitude: i32,
5569 #[doc = "Altitude (MSL). Positive for up."]
5570 pub altitude: i32,
5571 #[doc = "Local X position of this position in the local coordinate frame (NED)"]
5572 pub x: f32,
5573 #[doc = "Local Y position of this position in the local coordinate frame (NED)"]
5574 pub y: f32,
5575 #[doc = "Local Z position of this position in the local coordinate frame (NED: positive \"down\")"]
5576 pub z: f32,
5577 #[doc = "World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground"]
5578 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5579 pub q: [f32; 4],
5580 #[doc = "Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone."]
5581 pub approach_x: f32,
5582 #[doc = "Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone."]
5583 pub approach_y: f32,
5584 #[doc = "Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone."]
5585 pub approach_z: f32,
5586 #[doc = "System ID."]
5587 pub target_system: u8,
5588 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
5589 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
5590 pub time_usec: u64,
5591}
5592impl SET_HOME_POSITION_DATA {
5593 pub const ENCODED_LEN: usize = 61usize;
5594 pub const DEFAULT: Self = Self {
5595 latitude: 0_i32,
5596 longitude: 0_i32,
5597 altitude: 0_i32,
5598 x: 0.0_f32,
5599 y: 0.0_f32,
5600 z: 0.0_f32,
5601 q: [0.0_f32; 4usize],
5602 approach_x: 0.0_f32,
5603 approach_y: 0.0_f32,
5604 approach_z: 0.0_f32,
5605 target_system: 0_u8,
5606 time_usec: 0_u64,
5607 };
5608 #[cfg(feature = "arbitrary")]
5609 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
5610 use arbitrary::{Arbitrary, Unstructured};
5611 let mut buf = [0u8; 1024];
5612 rng.fill_bytes(&mut buf);
5613 let mut unstructured = Unstructured::new(&buf);
5614 Self::arbitrary(&mut unstructured).unwrap_or_default()
5615 }
5616}
5617impl Default for SET_HOME_POSITION_DATA {
5618 fn default() -> Self {
5619 Self::DEFAULT.clone()
5620 }
5621}
5622impl MessageData for SET_HOME_POSITION_DATA {
5623 type Message = MavMessage;
5624 const ID: u32 = 243u32;
5625 const NAME: &'static str = "SET_HOME_POSITION";
5626 const EXTRA_CRC: u8 = 85u8;
5627 const ENCODED_LEN: usize = 61usize;
5628 fn deser(
5629 _version: MavlinkVersion,
5630 __input: &[u8],
5631 ) -> Result<Self, ::mavlink_core::error::ParserError> {
5632 let avail_len = __input.len();
5633 let mut payload_buf = [0; Self::ENCODED_LEN];
5634 let mut buf = if avail_len < Self::ENCODED_LEN {
5635 payload_buf[0..avail_len].copy_from_slice(__input);
5636 Bytes::new(&payload_buf)
5637 } else {
5638 Bytes::new(__input)
5639 };
5640 let mut __struct = Self::default();
5641 __struct.latitude = buf.get_i32_le();
5642 __struct.longitude = buf.get_i32_le();
5643 __struct.altitude = buf.get_i32_le();
5644 __struct.x = buf.get_f32_le();
5645 __struct.y = buf.get_f32_le();
5646 __struct.z = buf.get_f32_le();
5647 for v in &mut __struct.q {
5648 let val = buf.get_f32_le();
5649 *v = val;
5650 }
5651 __struct.approach_x = buf.get_f32_le();
5652 __struct.approach_y = buf.get_f32_le();
5653 __struct.approach_z = buf.get_f32_le();
5654 __struct.target_system = buf.get_u8();
5655 __struct.time_usec = buf.get_u64_le();
5656 Ok(__struct)
5657 }
5658 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
5659 let mut __tmp = BytesMut::new(bytes);
5660 #[allow(clippy::absurd_extreme_comparisons)]
5661 #[allow(unused_comparisons)]
5662 if __tmp.remaining() < Self::ENCODED_LEN {
5663 panic!(
5664 "buffer is too small (need {} bytes, but got {})",
5665 Self::ENCODED_LEN,
5666 __tmp.remaining(),
5667 )
5668 }
5669 __tmp.put_i32_le(self.latitude);
5670 __tmp.put_i32_le(self.longitude);
5671 __tmp.put_i32_le(self.altitude);
5672 __tmp.put_f32_le(self.x);
5673 __tmp.put_f32_le(self.y);
5674 __tmp.put_f32_le(self.z);
5675 for val in &self.q {
5676 __tmp.put_f32_le(*val);
5677 }
5678 __tmp.put_f32_le(self.approach_x);
5679 __tmp.put_f32_le(self.approach_y);
5680 __tmp.put_f32_le(self.approach_z);
5681 __tmp.put_u8(self.target_system);
5682 __tmp.put_u64_le(self.time_usec);
5683 if matches!(version, MavlinkVersion::V2) {
5684 let len = __tmp.len();
5685 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
5686 } else {
5687 __tmp.len()
5688 }
5689 }
5690}
5691#[doc = "id: 253"]
5692#[doc = "Status text message. These messages are printed in yellow in the COMM console of QGroundControl. WARNING: They consume quite some bandwidth, so use only for important status and error messages. If implemented wisely, these messages are buffered on the MCU and sent only at a limited rate (e.g. 10 Hz)."]
5693#[derive(Debug, Clone, PartialEq)]
5694#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5695#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5696pub struct STATUSTEXT_DATA {
5697 #[doc = "Severity of status. Relies on the definitions within RFC-5424."]
5698 pub severity: MavSeverity,
5699 #[doc = "Status text message, without null termination character"]
5700 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5701 pub text: [u8; 50],
5702 #[doc = "Unique (opaque) identifier for this statustext message. May be used to reassemble a logical long-statustext message from a sequence of chunks. A value of zero indicates this is the only chunk in the sequence and the message can be emitted immediately."]
5703 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
5704 pub id: u16,
5705 #[doc = "This chunk's sequence number; indexing is from zero. Any null character in the text field is taken to mean this was the last chunk."]
5706 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
5707 pub chunk_seq: u8,
5708}
5709impl STATUSTEXT_DATA {
5710 pub const ENCODED_LEN: usize = 54usize;
5711 pub const DEFAULT: Self = Self {
5712 severity: MavSeverity::DEFAULT,
5713 text: [0_u8; 50usize],
5714 id: 0_u16,
5715 chunk_seq: 0_u8,
5716 };
5717 #[cfg(feature = "arbitrary")]
5718 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
5719 use arbitrary::{Arbitrary, Unstructured};
5720 let mut buf = [0u8; 1024];
5721 rng.fill_bytes(&mut buf);
5722 let mut unstructured = Unstructured::new(&buf);
5723 Self::arbitrary(&mut unstructured).unwrap_or_default()
5724 }
5725}
5726impl Default for STATUSTEXT_DATA {
5727 fn default() -> Self {
5728 Self::DEFAULT.clone()
5729 }
5730}
5731impl MessageData for STATUSTEXT_DATA {
5732 type Message = MavMessage;
5733 const ID: u32 = 253u32;
5734 const NAME: &'static str = "STATUSTEXT";
5735 const EXTRA_CRC: u8 = 83u8;
5736 const ENCODED_LEN: usize = 54usize;
5737 fn deser(
5738 _version: MavlinkVersion,
5739 __input: &[u8],
5740 ) -> Result<Self, ::mavlink_core::error::ParserError> {
5741 let avail_len = __input.len();
5742 let mut payload_buf = [0; Self::ENCODED_LEN];
5743 let mut buf = if avail_len < Self::ENCODED_LEN {
5744 payload_buf[0..avail_len].copy_from_slice(__input);
5745 Bytes::new(&payload_buf)
5746 } else {
5747 Bytes::new(__input)
5748 };
5749 let mut __struct = Self::default();
5750 let tmp = buf.get_u8();
5751 __struct.severity =
5752 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
5753 enum_type: "MavSeverity",
5754 value: tmp as u32,
5755 })?;
5756 for v in &mut __struct.text {
5757 let val = buf.get_u8();
5758 *v = val;
5759 }
5760 __struct.id = buf.get_u16_le();
5761 __struct.chunk_seq = buf.get_u8();
5762 Ok(__struct)
5763 }
5764 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
5765 let mut __tmp = BytesMut::new(bytes);
5766 #[allow(clippy::absurd_extreme_comparisons)]
5767 #[allow(unused_comparisons)]
5768 if __tmp.remaining() < Self::ENCODED_LEN {
5769 panic!(
5770 "buffer is too small (need {} bytes, but got {})",
5771 Self::ENCODED_LEN,
5772 __tmp.remaining(),
5773 )
5774 }
5775 __tmp.put_u8(self.severity as u8);
5776 for val in &self.text {
5777 __tmp.put_u8(*val);
5778 }
5779 __tmp.put_u16_le(self.id);
5780 __tmp.put_u8(self.chunk_seq);
5781 if matches!(version, MavlinkVersion::V2) {
5782 let len = __tmp.len();
5783 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
5784 } else {
5785 __tmp.len()
5786 }
5787 }
5788}
5789#[doc = "id: 30"]
5790#[doc = "The attitude in the aeronautical frame (right-handed, Z-down, Y-right, X-front, ZYX, intrinsic)."]
5791#[derive(Debug, Clone, PartialEq)]
5792#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5793#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5794pub struct ATTITUDE_DATA {
5795 #[doc = "Timestamp (time since system boot)."]
5796 pub time_boot_ms: u32,
5797 #[doc = "Roll angle (-pi..+pi)"]
5798 pub roll: f32,
5799 #[doc = "Pitch angle (-pi..+pi)"]
5800 pub pitch: f32,
5801 #[doc = "Yaw angle (-pi..+pi)"]
5802 pub yaw: f32,
5803 #[doc = "Roll angular speed"]
5804 pub rollspeed: f32,
5805 #[doc = "Pitch angular speed"]
5806 pub pitchspeed: f32,
5807 #[doc = "Yaw angular speed"]
5808 pub yawspeed: f32,
5809}
5810impl ATTITUDE_DATA {
5811 pub const ENCODED_LEN: usize = 28usize;
5812 pub const DEFAULT: Self = Self {
5813 time_boot_ms: 0_u32,
5814 roll: 0.0_f32,
5815 pitch: 0.0_f32,
5816 yaw: 0.0_f32,
5817 rollspeed: 0.0_f32,
5818 pitchspeed: 0.0_f32,
5819 yawspeed: 0.0_f32,
5820 };
5821 #[cfg(feature = "arbitrary")]
5822 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
5823 use arbitrary::{Arbitrary, Unstructured};
5824 let mut buf = [0u8; 1024];
5825 rng.fill_bytes(&mut buf);
5826 let mut unstructured = Unstructured::new(&buf);
5827 Self::arbitrary(&mut unstructured).unwrap_or_default()
5828 }
5829}
5830impl Default for ATTITUDE_DATA {
5831 fn default() -> Self {
5832 Self::DEFAULT.clone()
5833 }
5834}
5835impl MessageData for ATTITUDE_DATA {
5836 type Message = MavMessage;
5837 const ID: u32 = 30u32;
5838 const NAME: &'static str = "ATTITUDE";
5839 const EXTRA_CRC: u8 = 39u8;
5840 const ENCODED_LEN: usize = 28usize;
5841 fn deser(
5842 _version: MavlinkVersion,
5843 __input: &[u8],
5844 ) -> Result<Self, ::mavlink_core::error::ParserError> {
5845 let avail_len = __input.len();
5846 let mut payload_buf = [0; Self::ENCODED_LEN];
5847 let mut buf = if avail_len < Self::ENCODED_LEN {
5848 payload_buf[0..avail_len].copy_from_slice(__input);
5849 Bytes::new(&payload_buf)
5850 } else {
5851 Bytes::new(__input)
5852 };
5853 let mut __struct = Self::default();
5854 __struct.time_boot_ms = buf.get_u32_le();
5855 __struct.roll = buf.get_f32_le();
5856 __struct.pitch = buf.get_f32_le();
5857 __struct.yaw = buf.get_f32_le();
5858 __struct.rollspeed = buf.get_f32_le();
5859 __struct.pitchspeed = buf.get_f32_le();
5860 __struct.yawspeed = buf.get_f32_le();
5861 Ok(__struct)
5862 }
5863 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
5864 let mut __tmp = BytesMut::new(bytes);
5865 #[allow(clippy::absurd_extreme_comparisons)]
5866 #[allow(unused_comparisons)]
5867 if __tmp.remaining() < Self::ENCODED_LEN {
5868 panic!(
5869 "buffer is too small (need {} bytes, but got {})",
5870 Self::ENCODED_LEN,
5871 __tmp.remaining(),
5872 )
5873 }
5874 __tmp.put_u32_le(self.time_boot_ms);
5875 __tmp.put_f32_le(self.roll);
5876 __tmp.put_f32_le(self.pitch);
5877 __tmp.put_f32_le(self.yaw);
5878 __tmp.put_f32_le(self.rollspeed);
5879 __tmp.put_f32_le(self.pitchspeed);
5880 __tmp.put_f32_le(self.yawspeed);
5881 if matches!(version, MavlinkVersion::V2) {
5882 let len = __tmp.len();
5883 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
5884 } else {
5885 __tmp.len()
5886 }
5887 }
5888}
5889#[doc = "id: 12902"]
5890#[doc = "Data for filling the OpenDroneID Authentication message. The Authentication Message defines a field that can provide a means of authenticity for the identity of the UAS (Unmanned Aircraft System). The Authentication message can have two different formats. For data page 0, the fields PageCount, Length and TimeStamp are present and AuthData is only 17 bytes. For data page 1 through 15, PageCount, Length and TimeStamp are not present and the size of AuthData is 23 bytes."]
5891#[derive(Debug, Clone, PartialEq)]
5892#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5893#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5894pub struct OPEN_DRONE_ID_AUTHENTICATION_DATA {
5895 #[doc = "This field is only present for page 0. 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019."]
5896 pub timestamp: u32,
5897 #[doc = "System ID (0 for broadcast)."]
5898 pub target_system: u8,
5899 #[doc = "Component ID (0 for broadcast)."]
5900 pub target_component: u8,
5901 #[doc = "Only used for drone ID data received from other UAs. See detailed description at <https://mavlink.io/en/services/opendroneid.html>."]
5902 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5903 pub id_or_mac: [u8; 20],
5904 #[doc = "Indicates the type of authentication."]
5905 pub authentication_type: MavOdidAuthType,
5906 #[doc = "Allowed range is 0 - 15."]
5907 pub data_page: u8,
5908 #[doc = "This field is only present for page 0. Allowed range is 0 - 15. See the description of struct ODID_Auth_data at <https://github.com/opendroneid/opendroneid-core-c/blob/master/libopendroneid/opendroneid.h>."]
5909 pub last_page_index: u8,
5910 #[doc = "This field is only present for page 0. Total bytes of authentication_data from all data pages. See the description of struct ODID_Auth_data at <https://github.com/opendroneid/opendroneid-core-c/blob/master/libopendroneid/opendroneid.h>."]
5911 pub length: u8,
5912 #[doc = "Opaque authentication data. For page 0, the size is only 17 bytes. For other pages, the size is 23 bytes. Shall be filled with nulls in the unused portion of the field."]
5913 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5914 pub authentication_data: [u8; 23],
5915}
5916impl OPEN_DRONE_ID_AUTHENTICATION_DATA {
5917 pub const ENCODED_LEN: usize = 53usize;
5918 pub const DEFAULT: Self = Self {
5919 timestamp: 0_u32,
5920 target_system: 0_u8,
5921 target_component: 0_u8,
5922 id_or_mac: [0_u8; 20usize],
5923 authentication_type: MavOdidAuthType::DEFAULT,
5924 data_page: 0_u8,
5925 last_page_index: 0_u8,
5926 length: 0_u8,
5927 authentication_data: [0_u8; 23usize],
5928 };
5929 #[cfg(feature = "arbitrary")]
5930 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
5931 use arbitrary::{Arbitrary, Unstructured};
5932 let mut buf = [0u8; 1024];
5933 rng.fill_bytes(&mut buf);
5934 let mut unstructured = Unstructured::new(&buf);
5935 Self::arbitrary(&mut unstructured).unwrap_or_default()
5936 }
5937}
5938impl Default for OPEN_DRONE_ID_AUTHENTICATION_DATA {
5939 fn default() -> Self {
5940 Self::DEFAULT.clone()
5941 }
5942}
5943impl MessageData for OPEN_DRONE_ID_AUTHENTICATION_DATA {
5944 type Message = MavMessage;
5945 const ID: u32 = 12902u32;
5946 const NAME: &'static str = "OPEN_DRONE_ID_AUTHENTICATION";
5947 const EXTRA_CRC: u8 = 140u8;
5948 const ENCODED_LEN: usize = 53usize;
5949 fn deser(
5950 _version: MavlinkVersion,
5951 __input: &[u8],
5952 ) -> Result<Self, ::mavlink_core::error::ParserError> {
5953 let avail_len = __input.len();
5954 let mut payload_buf = [0; Self::ENCODED_LEN];
5955 let mut buf = if avail_len < Self::ENCODED_LEN {
5956 payload_buf[0..avail_len].copy_from_slice(__input);
5957 Bytes::new(&payload_buf)
5958 } else {
5959 Bytes::new(__input)
5960 };
5961 let mut __struct = Self::default();
5962 __struct.timestamp = buf.get_u32_le();
5963 __struct.target_system = buf.get_u8();
5964 __struct.target_component = buf.get_u8();
5965 for v in &mut __struct.id_or_mac {
5966 let val = buf.get_u8();
5967 *v = val;
5968 }
5969 let tmp = buf.get_u8();
5970 __struct.authentication_type =
5971 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
5972 enum_type: "MavOdidAuthType",
5973 value: tmp as u32,
5974 })?;
5975 __struct.data_page = buf.get_u8();
5976 __struct.last_page_index = buf.get_u8();
5977 __struct.length = buf.get_u8();
5978 for v in &mut __struct.authentication_data {
5979 let val = buf.get_u8();
5980 *v = val;
5981 }
5982 Ok(__struct)
5983 }
5984 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
5985 let mut __tmp = BytesMut::new(bytes);
5986 #[allow(clippy::absurd_extreme_comparisons)]
5987 #[allow(unused_comparisons)]
5988 if __tmp.remaining() < Self::ENCODED_LEN {
5989 panic!(
5990 "buffer is too small (need {} bytes, but got {})",
5991 Self::ENCODED_LEN,
5992 __tmp.remaining(),
5993 )
5994 }
5995 __tmp.put_u32_le(self.timestamp);
5996 __tmp.put_u8(self.target_system);
5997 __tmp.put_u8(self.target_component);
5998 for val in &self.id_or_mac {
5999 __tmp.put_u8(*val);
6000 }
6001 __tmp.put_u8(self.authentication_type as u8);
6002 __tmp.put_u8(self.data_page);
6003 __tmp.put_u8(self.last_page_index);
6004 __tmp.put_u8(self.length);
6005 for val in &self.authentication_data {
6006 __tmp.put_u8(*val);
6007 }
6008 if matches!(version, MavlinkVersion::V2) {
6009 let len = __tmp.len();
6010 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
6011 } else {
6012 __tmp.len()
6013 }
6014 }
6015}
6016#[doc = "id: 115"]
6017#[doc = "Sent from simulation to autopilot, avoids in contrast to HIL_STATE singularities. This packet is useful for high throughput applications such as hardware in the loop simulations."]
6018#[derive(Debug, Clone, PartialEq)]
6019#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6020#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6021pub struct HIL_STATE_QUATERNION_DATA {
6022 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
6023 pub time_usec: u64,
6024 #[doc = "Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation)"]
6025 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
6026 pub attitude_quaternion: [f32; 4],
6027 #[doc = "Body frame roll / phi angular speed"]
6028 pub rollspeed: f32,
6029 #[doc = "Body frame pitch / theta angular speed"]
6030 pub pitchspeed: f32,
6031 #[doc = "Body frame yaw / psi angular speed"]
6032 pub yawspeed: f32,
6033 #[doc = "Latitude"]
6034 pub lat: i32,
6035 #[doc = "Longitude"]
6036 pub lon: i32,
6037 #[doc = "Altitude"]
6038 pub alt: i32,
6039 #[doc = "Ground X Speed (Latitude)"]
6040 pub vx: i16,
6041 #[doc = "Ground Y Speed (Longitude)"]
6042 pub vy: i16,
6043 #[doc = "Ground Z Speed (Altitude)"]
6044 pub vz: i16,
6045 #[doc = "Indicated airspeed"]
6046 pub ind_airspeed: u16,
6047 #[doc = "True airspeed"]
6048 pub true_airspeed: u16,
6049 #[doc = "X acceleration"]
6050 pub xacc: i16,
6051 #[doc = "Y acceleration"]
6052 pub yacc: i16,
6053 #[doc = "Z acceleration"]
6054 pub zacc: i16,
6055}
6056impl HIL_STATE_QUATERNION_DATA {
6057 pub const ENCODED_LEN: usize = 64usize;
6058 pub const DEFAULT: Self = Self {
6059 time_usec: 0_u64,
6060 attitude_quaternion: [0.0_f32; 4usize],
6061 rollspeed: 0.0_f32,
6062 pitchspeed: 0.0_f32,
6063 yawspeed: 0.0_f32,
6064 lat: 0_i32,
6065 lon: 0_i32,
6066 alt: 0_i32,
6067 vx: 0_i16,
6068 vy: 0_i16,
6069 vz: 0_i16,
6070 ind_airspeed: 0_u16,
6071 true_airspeed: 0_u16,
6072 xacc: 0_i16,
6073 yacc: 0_i16,
6074 zacc: 0_i16,
6075 };
6076 #[cfg(feature = "arbitrary")]
6077 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
6078 use arbitrary::{Arbitrary, Unstructured};
6079 let mut buf = [0u8; 1024];
6080 rng.fill_bytes(&mut buf);
6081 let mut unstructured = Unstructured::new(&buf);
6082 Self::arbitrary(&mut unstructured).unwrap_or_default()
6083 }
6084}
6085impl Default for HIL_STATE_QUATERNION_DATA {
6086 fn default() -> Self {
6087 Self::DEFAULT.clone()
6088 }
6089}
6090impl MessageData for HIL_STATE_QUATERNION_DATA {
6091 type Message = MavMessage;
6092 const ID: u32 = 115u32;
6093 const NAME: &'static str = "HIL_STATE_QUATERNION";
6094 const EXTRA_CRC: u8 = 4u8;
6095 const ENCODED_LEN: usize = 64usize;
6096 fn deser(
6097 _version: MavlinkVersion,
6098 __input: &[u8],
6099 ) -> Result<Self, ::mavlink_core::error::ParserError> {
6100 let avail_len = __input.len();
6101 let mut payload_buf = [0; Self::ENCODED_LEN];
6102 let mut buf = if avail_len < Self::ENCODED_LEN {
6103 payload_buf[0..avail_len].copy_from_slice(__input);
6104 Bytes::new(&payload_buf)
6105 } else {
6106 Bytes::new(__input)
6107 };
6108 let mut __struct = Self::default();
6109 __struct.time_usec = buf.get_u64_le();
6110 for v in &mut __struct.attitude_quaternion {
6111 let val = buf.get_f32_le();
6112 *v = val;
6113 }
6114 __struct.rollspeed = buf.get_f32_le();
6115 __struct.pitchspeed = buf.get_f32_le();
6116 __struct.yawspeed = buf.get_f32_le();
6117 __struct.lat = buf.get_i32_le();
6118 __struct.lon = buf.get_i32_le();
6119 __struct.alt = buf.get_i32_le();
6120 __struct.vx = buf.get_i16_le();
6121 __struct.vy = buf.get_i16_le();
6122 __struct.vz = buf.get_i16_le();
6123 __struct.ind_airspeed = buf.get_u16_le();
6124 __struct.true_airspeed = buf.get_u16_le();
6125 __struct.xacc = buf.get_i16_le();
6126 __struct.yacc = buf.get_i16_le();
6127 __struct.zacc = buf.get_i16_le();
6128 Ok(__struct)
6129 }
6130 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
6131 let mut __tmp = BytesMut::new(bytes);
6132 #[allow(clippy::absurd_extreme_comparisons)]
6133 #[allow(unused_comparisons)]
6134 if __tmp.remaining() < Self::ENCODED_LEN {
6135 panic!(
6136 "buffer is too small (need {} bytes, but got {})",
6137 Self::ENCODED_LEN,
6138 __tmp.remaining(),
6139 )
6140 }
6141 __tmp.put_u64_le(self.time_usec);
6142 for val in &self.attitude_quaternion {
6143 __tmp.put_f32_le(*val);
6144 }
6145 __tmp.put_f32_le(self.rollspeed);
6146 __tmp.put_f32_le(self.pitchspeed);
6147 __tmp.put_f32_le(self.yawspeed);
6148 __tmp.put_i32_le(self.lat);
6149 __tmp.put_i32_le(self.lon);
6150 __tmp.put_i32_le(self.alt);
6151 __tmp.put_i16_le(self.vx);
6152 __tmp.put_i16_le(self.vy);
6153 __tmp.put_i16_le(self.vz);
6154 __tmp.put_u16_le(self.ind_airspeed);
6155 __tmp.put_u16_le(self.true_airspeed);
6156 __tmp.put_i16_le(self.xacc);
6157 __tmp.put_i16_le(self.yacc);
6158 __tmp.put_i16_le(self.zacc);
6159 if matches!(version, MavlinkVersion::V2) {
6160 let len = __tmp.len();
6161 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
6162 } else {
6163 __tmp.len()
6164 }
6165 }
6166}
6167#[doc = "id: 245"]
6168#[doc = "Provides state for additional features."]
6169#[derive(Debug, Clone, PartialEq)]
6170#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6171#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6172pub struct EXTENDED_SYS_STATE_DATA {
6173 #[doc = "The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration."]
6174 pub vtol_state: MavVtolState,
6175 #[doc = "The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown."]
6176 pub landed_state: MavLandedState,
6177}
6178impl EXTENDED_SYS_STATE_DATA {
6179 pub const ENCODED_LEN: usize = 2usize;
6180 pub const DEFAULT: Self = Self {
6181 vtol_state: MavVtolState::DEFAULT,
6182 landed_state: MavLandedState::DEFAULT,
6183 };
6184 #[cfg(feature = "arbitrary")]
6185 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
6186 use arbitrary::{Arbitrary, Unstructured};
6187 let mut buf = [0u8; 1024];
6188 rng.fill_bytes(&mut buf);
6189 let mut unstructured = Unstructured::new(&buf);
6190 Self::arbitrary(&mut unstructured).unwrap_or_default()
6191 }
6192}
6193impl Default for EXTENDED_SYS_STATE_DATA {
6194 fn default() -> Self {
6195 Self::DEFAULT.clone()
6196 }
6197}
6198impl MessageData for EXTENDED_SYS_STATE_DATA {
6199 type Message = MavMessage;
6200 const ID: u32 = 245u32;
6201 const NAME: &'static str = "EXTENDED_SYS_STATE";
6202 const EXTRA_CRC: u8 = 130u8;
6203 const ENCODED_LEN: usize = 2usize;
6204 fn deser(
6205 _version: MavlinkVersion,
6206 __input: &[u8],
6207 ) -> Result<Self, ::mavlink_core::error::ParserError> {
6208 let avail_len = __input.len();
6209 let mut payload_buf = [0; Self::ENCODED_LEN];
6210 let mut buf = if avail_len < Self::ENCODED_LEN {
6211 payload_buf[0..avail_len].copy_from_slice(__input);
6212 Bytes::new(&payload_buf)
6213 } else {
6214 Bytes::new(__input)
6215 };
6216 let mut __struct = Self::default();
6217 let tmp = buf.get_u8();
6218 __struct.vtol_state =
6219 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
6220 enum_type: "MavVtolState",
6221 value: tmp as u32,
6222 })?;
6223 let tmp = buf.get_u8();
6224 __struct.landed_state =
6225 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
6226 enum_type: "MavLandedState",
6227 value: tmp as u32,
6228 })?;
6229 Ok(__struct)
6230 }
6231 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
6232 let mut __tmp = BytesMut::new(bytes);
6233 #[allow(clippy::absurd_extreme_comparisons)]
6234 #[allow(unused_comparisons)]
6235 if __tmp.remaining() < Self::ENCODED_LEN {
6236 panic!(
6237 "buffer is too small (need {} bytes, but got {})",
6238 Self::ENCODED_LEN,
6239 __tmp.remaining(),
6240 )
6241 }
6242 __tmp.put_u8(self.vtol_state as u8);
6243 __tmp.put_u8(self.landed_state as u8);
6244 if matches!(version, MavlinkVersion::V2) {
6245 let len = __tmp.len();
6246 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
6247 } else {
6248 __tmp.len()
6249 }
6250 }
6251}
6252#[doc = "id: 332"]
6253#[doc = "Describe a trajectory using an array of up-to 5 waypoints in the local frame (MAV_FRAME_LOCAL_NED)."]
6254#[derive(Debug, Clone, PartialEq)]
6255#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6256#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6257pub struct TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA {
6258 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
6259 pub time_usec: u64,
6260 #[doc = "X-coordinate of waypoint, set to NaN if not being used"]
6261 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
6262 pub pos_x: [f32; 5],
6263 #[doc = "Y-coordinate of waypoint, set to NaN if not being used"]
6264 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
6265 pub pos_y: [f32; 5],
6266 #[doc = "Z-coordinate of waypoint, set to NaN if not being used"]
6267 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
6268 pub pos_z: [f32; 5],
6269 #[doc = "X-velocity of waypoint, set to NaN if not being used"]
6270 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
6271 pub vel_x: [f32; 5],
6272 #[doc = "Y-velocity of waypoint, set to NaN if not being used"]
6273 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
6274 pub vel_y: [f32; 5],
6275 #[doc = "Z-velocity of waypoint, set to NaN if not being used"]
6276 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
6277 pub vel_z: [f32; 5],
6278 #[doc = "X-acceleration of waypoint, set to NaN if not being used"]
6279 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
6280 pub acc_x: [f32; 5],
6281 #[doc = "Y-acceleration of waypoint, set to NaN if not being used"]
6282 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
6283 pub acc_y: [f32; 5],
6284 #[doc = "Z-acceleration of waypoint, set to NaN if not being used"]
6285 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
6286 pub acc_z: [f32; 5],
6287 #[doc = "Yaw angle, set to NaN if not being used"]
6288 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
6289 pub pos_yaw: [f32; 5],
6290 #[doc = "Yaw rate, set to NaN if not being used"]
6291 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
6292 pub vel_yaw: [f32; 5],
6293 #[doc = "MAV_CMD command id of waypoint, set to UINT16_MAX if not being used."]
6294 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
6295 pub command: [u16; 5],
6296 #[doc = "Number of valid points (up-to 5 waypoints are possible)"]
6297 pub valid_points: u8,
6298}
6299impl TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA {
6300 pub const ENCODED_LEN: usize = 239usize;
6301 pub const DEFAULT: Self = Self {
6302 time_usec: 0_u64,
6303 pos_x: [0.0_f32; 5usize],
6304 pos_y: [0.0_f32; 5usize],
6305 pos_z: [0.0_f32; 5usize],
6306 vel_x: [0.0_f32; 5usize],
6307 vel_y: [0.0_f32; 5usize],
6308 vel_z: [0.0_f32; 5usize],
6309 acc_x: [0.0_f32; 5usize],
6310 acc_y: [0.0_f32; 5usize],
6311 acc_z: [0.0_f32; 5usize],
6312 pos_yaw: [0.0_f32; 5usize],
6313 vel_yaw: [0.0_f32; 5usize],
6314 command: [0_u16; 5usize],
6315 valid_points: 0_u8,
6316 };
6317 #[cfg(feature = "arbitrary")]
6318 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
6319 use arbitrary::{Arbitrary, Unstructured};
6320 let mut buf = [0u8; 1024];
6321 rng.fill_bytes(&mut buf);
6322 let mut unstructured = Unstructured::new(&buf);
6323 Self::arbitrary(&mut unstructured).unwrap_or_default()
6324 }
6325}
6326impl Default for TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA {
6327 fn default() -> Self {
6328 Self::DEFAULT.clone()
6329 }
6330}
6331impl MessageData for TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA {
6332 type Message = MavMessage;
6333 const ID: u32 = 332u32;
6334 const NAME: &'static str = "TRAJECTORY_REPRESENTATION_WAYPOINTS";
6335 const EXTRA_CRC: u8 = 236u8;
6336 const ENCODED_LEN: usize = 239usize;
6337 fn deser(
6338 _version: MavlinkVersion,
6339 __input: &[u8],
6340 ) -> Result<Self, ::mavlink_core::error::ParserError> {
6341 let avail_len = __input.len();
6342 let mut payload_buf = [0; Self::ENCODED_LEN];
6343 let mut buf = if avail_len < Self::ENCODED_LEN {
6344 payload_buf[0..avail_len].copy_from_slice(__input);
6345 Bytes::new(&payload_buf)
6346 } else {
6347 Bytes::new(__input)
6348 };
6349 let mut __struct = Self::default();
6350 __struct.time_usec = buf.get_u64_le();
6351 for v in &mut __struct.pos_x {
6352 let val = buf.get_f32_le();
6353 *v = val;
6354 }
6355 for v in &mut __struct.pos_y {
6356 let val = buf.get_f32_le();
6357 *v = val;
6358 }
6359 for v in &mut __struct.pos_z {
6360 let val = buf.get_f32_le();
6361 *v = val;
6362 }
6363 for v in &mut __struct.vel_x {
6364 let val = buf.get_f32_le();
6365 *v = val;
6366 }
6367 for v in &mut __struct.vel_y {
6368 let val = buf.get_f32_le();
6369 *v = val;
6370 }
6371 for v in &mut __struct.vel_z {
6372 let val = buf.get_f32_le();
6373 *v = val;
6374 }
6375 for v in &mut __struct.acc_x {
6376 let val = buf.get_f32_le();
6377 *v = val;
6378 }
6379 for v in &mut __struct.acc_y {
6380 let val = buf.get_f32_le();
6381 *v = val;
6382 }
6383 for v in &mut __struct.acc_z {
6384 let val = buf.get_f32_le();
6385 *v = val;
6386 }
6387 for v in &mut __struct.pos_yaw {
6388 let val = buf.get_f32_le();
6389 *v = val;
6390 }
6391 for v in &mut __struct.vel_yaw {
6392 let val = buf.get_f32_le();
6393 *v = val;
6394 }
6395 for v in &mut __struct.command {
6396 let val = buf.get_u16_le();
6397 *v = val;
6398 }
6399 __struct.valid_points = buf.get_u8();
6400 Ok(__struct)
6401 }
6402 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
6403 let mut __tmp = BytesMut::new(bytes);
6404 #[allow(clippy::absurd_extreme_comparisons)]
6405 #[allow(unused_comparisons)]
6406 if __tmp.remaining() < Self::ENCODED_LEN {
6407 panic!(
6408 "buffer is too small (need {} bytes, but got {})",
6409 Self::ENCODED_LEN,
6410 __tmp.remaining(),
6411 )
6412 }
6413 __tmp.put_u64_le(self.time_usec);
6414 for val in &self.pos_x {
6415 __tmp.put_f32_le(*val);
6416 }
6417 for val in &self.pos_y {
6418 __tmp.put_f32_le(*val);
6419 }
6420 for val in &self.pos_z {
6421 __tmp.put_f32_le(*val);
6422 }
6423 for val in &self.vel_x {
6424 __tmp.put_f32_le(*val);
6425 }
6426 for val in &self.vel_y {
6427 __tmp.put_f32_le(*val);
6428 }
6429 for val in &self.vel_z {
6430 __tmp.put_f32_le(*val);
6431 }
6432 for val in &self.acc_x {
6433 __tmp.put_f32_le(*val);
6434 }
6435 for val in &self.acc_y {
6436 __tmp.put_f32_le(*val);
6437 }
6438 for val in &self.acc_z {
6439 __tmp.put_f32_le(*val);
6440 }
6441 for val in &self.pos_yaw {
6442 __tmp.put_f32_le(*val);
6443 }
6444 for val in &self.vel_yaw {
6445 __tmp.put_f32_le(*val);
6446 }
6447 for val in &self.command {
6448 __tmp.put_u16_le(*val);
6449 }
6450 __tmp.put_u8(self.valid_points);
6451 if matches!(version, MavlinkVersion::V2) {
6452 let len = __tmp.len();
6453 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
6454 } else {
6455 __tmp.len()
6456 }
6457 }
6458}
6459#[doc = "id: 247"]
6460#[doc = "Information about a potential collision."]
6461#[derive(Debug, Clone, PartialEq)]
6462#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6463#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6464pub struct COLLISION_DATA {
6465 #[doc = "Unique identifier, domain based on src field"]
6466 pub id: u32,
6467 #[doc = "Estimated time until collision occurs"]
6468 pub time_to_minimum_delta: f32,
6469 #[doc = "Closest vertical distance between vehicle and object"]
6470 pub altitude_minimum_delta: f32,
6471 #[doc = "Closest horizontal distance between vehicle and object"]
6472 pub horizontal_minimum_delta: f32,
6473 #[doc = "Collision data source"]
6474 pub src: MavCollisionSrc,
6475 #[doc = "Action that is being taken to avoid this collision"]
6476 pub action: MavCollisionAction,
6477 #[doc = "How concerned the aircraft is about this collision"]
6478 pub threat_level: MavCollisionThreatLevel,
6479}
6480impl COLLISION_DATA {
6481 pub const ENCODED_LEN: usize = 19usize;
6482 pub const DEFAULT: Self = Self {
6483 id: 0_u32,
6484 time_to_minimum_delta: 0.0_f32,
6485 altitude_minimum_delta: 0.0_f32,
6486 horizontal_minimum_delta: 0.0_f32,
6487 src: MavCollisionSrc::DEFAULT,
6488 action: MavCollisionAction::DEFAULT,
6489 threat_level: MavCollisionThreatLevel::DEFAULT,
6490 };
6491 #[cfg(feature = "arbitrary")]
6492 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
6493 use arbitrary::{Arbitrary, Unstructured};
6494 let mut buf = [0u8; 1024];
6495 rng.fill_bytes(&mut buf);
6496 let mut unstructured = Unstructured::new(&buf);
6497 Self::arbitrary(&mut unstructured).unwrap_or_default()
6498 }
6499}
6500impl Default for COLLISION_DATA {
6501 fn default() -> Self {
6502 Self::DEFAULT.clone()
6503 }
6504}
6505impl MessageData for COLLISION_DATA {
6506 type Message = MavMessage;
6507 const ID: u32 = 247u32;
6508 const NAME: &'static str = "COLLISION";
6509 const EXTRA_CRC: u8 = 81u8;
6510 const ENCODED_LEN: usize = 19usize;
6511 fn deser(
6512 _version: MavlinkVersion,
6513 __input: &[u8],
6514 ) -> Result<Self, ::mavlink_core::error::ParserError> {
6515 let avail_len = __input.len();
6516 let mut payload_buf = [0; Self::ENCODED_LEN];
6517 let mut buf = if avail_len < Self::ENCODED_LEN {
6518 payload_buf[0..avail_len].copy_from_slice(__input);
6519 Bytes::new(&payload_buf)
6520 } else {
6521 Bytes::new(__input)
6522 };
6523 let mut __struct = Self::default();
6524 __struct.id = buf.get_u32_le();
6525 __struct.time_to_minimum_delta = buf.get_f32_le();
6526 __struct.altitude_minimum_delta = buf.get_f32_le();
6527 __struct.horizontal_minimum_delta = buf.get_f32_le();
6528 let tmp = buf.get_u8();
6529 __struct.src =
6530 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
6531 enum_type: "MavCollisionSrc",
6532 value: tmp as u32,
6533 })?;
6534 let tmp = buf.get_u8();
6535 __struct.action =
6536 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
6537 enum_type: "MavCollisionAction",
6538 value: tmp as u32,
6539 })?;
6540 let tmp = buf.get_u8();
6541 __struct.threat_level =
6542 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
6543 enum_type: "MavCollisionThreatLevel",
6544 value: tmp as u32,
6545 })?;
6546 Ok(__struct)
6547 }
6548 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
6549 let mut __tmp = BytesMut::new(bytes);
6550 #[allow(clippy::absurd_extreme_comparisons)]
6551 #[allow(unused_comparisons)]
6552 if __tmp.remaining() < Self::ENCODED_LEN {
6553 panic!(
6554 "buffer is too small (need {} bytes, but got {})",
6555 Self::ENCODED_LEN,
6556 __tmp.remaining(),
6557 )
6558 }
6559 __tmp.put_u32_le(self.id);
6560 __tmp.put_f32_le(self.time_to_minimum_delta);
6561 __tmp.put_f32_le(self.altitude_minimum_delta);
6562 __tmp.put_f32_le(self.horizontal_minimum_delta);
6563 __tmp.put_u8(self.src as u8);
6564 __tmp.put_u8(self.action as u8);
6565 __tmp.put_u8(self.threat_level as u8);
6566 if matches!(version, MavlinkVersion::V2) {
6567 let len = __tmp.len();
6568 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
6569 } else {
6570 __tmp.len()
6571 }
6572 }
6573}
6574#[doc = "id: 47"]
6575#[doc = "Acknowledgment message during waypoint handling. The type field states if this message is a positive ack (type=0) or if an error happened (type=non-zero)."]
6576#[derive(Debug, Clone, PartialEq)]
6577#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6578#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6579pub struct MISSION_ACK_DATA {
6580 #[doc = "System ID"]
6581 pub target_system: u8,
6582 #[doc = "Component ID"]
6583 pub target_component: u8,
6584 #[doc = "Mission result."]
6585 pub mavtype: MavMissionResult,
6586 #[doc = "Mission type."]
6587 #[cfg_attr(feature = "serde", serde(default))]
6588 pub mission_type: MavMissionType,
6589 #[doc = "Id of new on-vehicle mission, fence, or rally point plan (on upload to vehicle). The id is calculated and returned by a vehicle when a new plan is uploaded by a GCS. The only requirement on the id is that it must change when there is any change to the on-vehicle plan type (there is no requirement that the id be globally unique). 0 on download from the vehicle to the GCS (on download the ID is set in MISSION_COUNT). 0 if plan ids are not supported. The current on-vehicle plan ids are streamed in `MISSION_CURRENT`, allowing a GCS to determine if any part of the plan has changed and needs to be re-uploaded."]
6590 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
6591 pub opaque_id: u32,
6592}
6593impl MISSION_ACK_DATA {
6594 pub const ENCODED_LEN: usize = 8usize;
6595 pub const DEFAULT: Self = Self {
6596 target_system: 0_u8,
6597 target_component: 0_u8,
6598 mavtype: MavMissionResult::DEFAULT,
6599 mission_type: MavMissionType::DEFAULT,
6600 opaque_id: 0_u32,
6601 };
6602 #[cfg(feature = "arbitrary")]
6603 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
6604 use arbitrary::{Arbitrary, Unstructured};
6605 let mut buf = [0u8; 1024];
6606 rng.fill_bytes(&mut buf);
6607 let mut unstructured = Unstructured::new(&buf);
6608 Self::arbitrary(&mut unstructured).unwrap_or_default()
6609 }
6610}
6611impl Default for MISSION_ACK_DATA {
6612 fn default() -> Self {
6613 Self::DEFAULT.clone()
6614 }
6615}
6616impl MessageData for MISSION_ACK_DATA {
6617 type Message = MavMessage;
6618 const ID: u32 = 47u32;
6619 const NAME: &'static str = "MISSION_ACK";
6620 const EXTRA_CRC: u8 = 153u8;
6621 const ENCODED_LEN: usize = 8usize;
6622 fn deser(
6623 _version: MavlinkVersion,
6624 __input: &[u8],
6625 ) -> Result<Self, ::mavlink_core::error::ParserError> {
6626 let avail_len = __input.len();
6627 let mut payload_buf = [0; Self::ENCODED_LEN];
6628 let mut buf = if avail_len < Self::ENCODED_LEN {
6629 payload_buf[0..avail_len].copy_from_slice(__input);
6630 Bytes::new(&payload_buf)
6631 } else {
6632 Bytes::new(__input)
6633 };
6634 let mut __struct = Self::default();
6635 __struct.target_system = buf.get_u8();
6636 __struct.target_component = buf.get_u8();
6637 let tmp = buf.get_u8();
6638 __struct.mavtype =
6639 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
6640 enum_type: "MavMissionResult",
6641 value: tmp as u32,
6642 })?;
6643 let tmp = buf.get_u8();
6644 __struct.mission_type =
6645 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
6646 enum_type: "MavMissionType",
6647 value: tmp as u32,
6648 })?;
6649 __struct.opaque_id = buf.get_u32_le();
6650 Ok(__struct)
6651 }
6652 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
6653 let mut __tmp = BytesMut::new(bytes);
6654 #[allow(clippy::absurd_extreme_comparisons)]
6655 #[allow(unused_comparisons)]
6656 if __tmp.remaining() < Self::ENCODED_LEN {
6657 panic!(
6658 "buffer is too small (need {} bytes, but got {})",
6659 Self::ENCODED_LEN,
6660 __tmp.remaining(),
6661 )
6662 }
6663 __tmp.put_u8(self.target_system);
6664 __tmp.put_u8(self.target_component);
6665 __tmp.put_u8(self.mavtype as u8);
6666 __tmp.put_u8(self.mission_type as u8);
6667 __tmp.put_u32_le(self.opaque_id);
6668 if matches!(version, MavlinkVersion::V2) {
6669 let len = __tmp.len();
6670 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
6671 } else {
6672 __tmp.len()
6673 }
6674 }
6675}
6676#[doc = "id: 86"]
6677#[doc = "Sets a desired vehicle position, velocity, and/or acceleration in a global coordinate system (WGS84). Used by an external controller to command the vehicle (manual controller or other system)."]
6678#[derive(Debug, Clone, PartialEq)]
6679#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6680#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6681pub struct SET_POSITION_TARGET_GLOBAL_INT_DATA {
6682 #[doc = "Timestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency."]
6683 pub time_boot_ms: u32,
6684 #[doc = "Latitude in WGS84 frame"]
6685 pub lat_int: i32,
6686 #[doc = "Longitude in WGS84 frame"]
6687 pub lon_int: i32,
6688 #[doc = "Altitude (MSL, Relative to home, or AGL - depending on frame)"]
6689 pub alt: f32,
6690 #[doc = "X velocity in NED frame"]
6691 pub vx: f32,
6692 #[doc = "Y velocity in NED frame"]
6693 pub vy: f32,
6694 #[doc = "Z velocity in NED frame"]
6695 pub vz: f32,
6696 #[doc = "X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
6697 pub afx: f32,
6698 #[doc = "Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
6699 pub afy: f32,
6700 #[doc = "Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
6701 pub afz: f32,
6702 #[doc = "yaw setpoint"]
6703 pub yaw: f32,
6704 #[doc = "yaw rate setpoint"]
6705 pub yaw_rate: f32,
6706 #[doc = "Bitmap to indicate which dimensions should be ignored by the vehicle."]
6707 pub type_mask: PositionTargetTypemask,
6708 #[doc = "System ID"]
6709 pub target_system: u8,
6710 #[doc = "Component ID"]
6711 pub target_component: u8,
6712 #[doc = "Valid options are: MAV_FRAME_GLOBAL = 0, MAV_FRAME_GLOBAL_RELATIVE_ALT = 3, MAV_FRAME_GLOBAL_TERRAIN_ALT = 10 (MAV_FRAME_GLOBAL_INT, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT are allowed synonyms, but have been deprecated)"]
6713 pub coordinate_frame: MavFrame,
6714}
6715impl SET_POSITION_TARGET_GLOBAL_INT_DATA {
6716 pub const ENCODED_LEN: usize = 53usize;
6717 pub const DEFAULT: Self = Self {
6718 time_boot_ms: 0_u32,
6719 lat_int: 0_i32,
6720 lon_int: 0_i32,
6721 alt: 0.0_f32,
6722 vx: 0.0_f32,
6723 vy: 0.0_f32,
6724 vz: 0.0_f32,
6725 afx: 0.0_f32,
6726 afy: 0.0_f32,
6727 afz: 0.0_f32,
6728 yaw: 0.0_f32,
6729 yaw_rate: 0.0_f32,
6730 type_mask: PositionTargetTypemask::DEFAULT,
6731 target_system: 0_u8,
6732 target_component: 0_u8,
6733 coordinate_frame: MavFrame::DEFAULT,
6734 };
6735 #[cfg(feature = "arbitrary")]
6736 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
6737 use arbitrary::{Arbitrary, Unstructured};
6738 let mut buf = [0u8; 1024];
6739 rng.fill_bytes(&mut buf);
6740 let mut unstructured = Unstructured::new(&buf);
6741 Self::arbitrary(&mut unstructured).unwrap_or_default()
6742 }
6743}
6744impl Default for SET_POSITION_TARGET_GLOBAL_INT_DATA {
6745 fn default() -> Self {
6746 Self::DEFAULT.clone()
6747 }
6748}
6749impl MessageData for SET_POSITION_TARGET_GLOBAL_INT_DATA {
6750 type Message = MavMessage;
6751 const ID: u32 = 86u32;
6752 const NAME: &'static str = "SET_POSITION_TARGET_GLOBAL_INT";
6753 const EXTRA_CRC: u8 = 5u8;
6754 const ENCODED_LEN: usize = 53usize;
6755 fn deser(
6756 _version: MavlinkVersion,
6757 __input: &[u8],
6758 ) -> Result<Self, ::mavlink_core::error::ParserError> {
6759 let avail_len = __input.len();
6760 let mut payload_buf = [0; Self::ENCODED_LEN];
6761 let mut buf = if avail_len < Self::ENCODED_LEN {
6762 payload_buf[0..avail_len].copy_from_slice(__input);
6763 Bytes::new(&payload_buf)
6764 } else {
6765 Bytes::new(__input)
6766 };
6767 let mut __struct = Self::default();
6768 __struct.time_boot_ms = buf.get_u32_le();
6769 __struct.lat_int = buf.get_i32_le();
6770 __struct.lon_int = buf.get_i32_le();
6771 __struct.alt = buf.get_f32_le();
6772 __struct.vx = buf.get_f32_le();
6773 __struct.vy = buf.get_f32_le();
6774 __struct.vz = buf.get_f32_le();
6775 __struct.afx = buf.get_f32_le();
6776 __struct.afy = buf.get_f32_le();
6777 __struct.afz = buf.get_f32_le();
6778 __struct.yaw = buf.get_f32_le();
6779 __struct.yaw_rate = buf.get_f32_le();
6780 let tmp = buf.get_u16_le();
6781 __struct.type_mask = PositionTargetTypemask::from_bits(
6782 tmp & PositionTargetTypemask::all().bits(),
6783 )
6784 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
6785 flag_type: "PositionTargetTypemask",
6786 value: tmp as u32,
6787 })?;
6788 __struct.target_system = buf.get_u8();
6789 __struct.target_component = buf.get_u8();
6790 let tmp = buf.get_u8();
6791 __struct.coordinate_frame =
6792 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
6793 enum_type: "MavFrame",
6794 value: tmp as u32,
6795 })?;
6796 Ok(__struct)
6797 }
6798 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
6799 let mut __tmp = BytesMut::new(bytes);
6800 #[allow(clippy::absurd_extreme_comparisons)]
6801 #[allow(unused_comparisons)]
6802 if __tmp.remaining() < Self::ENCODED_LEN {
6803 panic!(
6804 "buffer is too small (need {} bytes, but got {})",
6805 Self::ENCODED_LEN,
6806 __tmp.remaining(),
6807 )
6808 }
6809 __tmp.put_u32_le(self.time_boot_ms);
6810 __tmp.put_i32_le(self.lat_int);
6811 __tmp.put_i32_le(self.lon_int);
6812 __tmp.put_f32_le(self.alt);
6813 __tmp.put_f32_le(self.vx);
6814 __tmp.put_f32_le(self.vy);
6815 __tmp.put_f32_le(self.vz);
6816 __tmp.put_f32_le(self.afx);
6817 __tmp.put_f32_le(self.afy);
6818 __tmp.put_f32_le(self.afz);
6819 __tmp.put_f32_le(self.yaw);
6820 __tmp.put_f32_le(self.yaw_rate);
6821 __tmp.put_u16_le(self.type_mask.bits());
6822 __tmp.put_u8(self.target_system);
6823 __tmp.put_u8(self.target_component);
6824 __tmp.put_u8(self.coordinate_frame as u8);
6825 if matches!(version, MavlinkVersion::V2) {
6826 let len = __tmp.len();
6827 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
6828 } else {
6829 __tmp.len()
6830 }
6831 }
6832}
6833#[doc = "id: 290"]
6834#[doc = "ESC information for lower rate streaming. Recommended streaming rate 1Hz. See ESC_STATUS for higher-rate ESC data."]
6835#[derive(Debug, Clone, PartialEq)]
6836#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6837#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6838pub struct ESC_INFO_DATA {
6839 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number."]
6840 pub time_usec: u64,
6841 #[doc = "Number of reported errors by each ESC since boot."]
6842 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
6843 pub error_count: [u32; 4],
6844 #[doc = "Counter of data packets received."]
6845 pub counter: u16,
6846 #[doc = "Bitmap of ESC failure flags."]
6847 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
6848 pub failure_flags: [u16; 4],
6849 #[doc = "Temperature of each ESC. INT16_MAX: if data not supplied by ESC."]
6850 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
6851 pub temperature: [i16; 4],
6852 #[doc = "Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4."]
6853 pub index: u8,
6854 #[doc = "Total number of ESCs in all messages of this type. Message fields with an index higher than this should be ignored because they contain invalid data."]
6855 pub count: u8,
6856 #[doc = "Connection type protocol for all ESC."]
6857 pub connection_type: EscConnectionType,
6858 #[doc = "Information regarding online/offline status of each ESC."]
6859 pub info: u8,
6860}
6861impl ESC_INFO_DATA {
6862 pub const ENCODED_LEN: usize = 46usize;
6863 pub const DEFAULT: Self = Self {
6864 time_usec: 0_u64,
6865 error_count: [0_u32; 4usize],
6866 counter: 0_u16,
6867 failure_flags: [0_u16; 4usize],
6868 temperature: [0_i16; 4usize],
6869 index: 0_u8,
6870 count: 0_u8,
6871 connection_type: EscConnectionType::DEFAULT,
6872 info: 0_u8,
6873 };
6874 #[cfg(feature = "arbitrary")]
6875 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
6876 use arbitrary::{Arbitrary, Unstructured};
6877 let mut buf = [0u8; 1024];
6878 rng.fill_bytes(&mut buf);
6879 let mut unstructured = Unstructured::new(&buf);
6880 Self::arbitrary(&mut unstructured).unwrap_or_default()
6881 }
6882}
6883impl Default for ESC_INFO_DATA {
6884 fn default() -> Self {
6885 Self::DEFAULT.clone()
6886 }
6887}
6888impl MessageData for ESC_INFO_DATA {
6889 type Message = MavMessage;
6890 const ID: u32 = 290u32;
6891 const NAME: &'static str = "ESC_INFO";
6892 const EXTRA_CRC: u8 = 251u8;
6893 const ENCODED_LEN: usize = 46usize;
6894 fn deser(
6895 _version: MavlinkVersion,
6896 __input: &[u8],
6897 ) -> Result<Self, ::mavlink_core::error::ParserError> {
6898 let avail_len = __input.len();
6899 let mut payload_buf = [0; Self::ENCODED_LEN];
6900 let mut buf = if avail_len < Self::ENCODED_LEN {
6901 payload_buf[0..avail_len].copy_from_slice(__input);
6902 Bytes::new(&payload_buf)
6903 } else {
6904 Bytes::new(__input)
6905 };
6906 let mut __struct = Self::default();
6907 __struct.time_usec = buf.get_u64_le();
6908 for v in &mut __struct.error_count {
6909 let val = buf.get_u32_le();
6910 *v = val;
6911 }
6912 __struct.counter = buf.get_u16_le();
6913 for v in &mut __struct.failure_flags {
6914 let val = buf.get_u16_le();
6915 *v = val;
6916 }
6917 for v in &mut __struct.temperature {
6918 let val = buf.get_i16_le();
6919 *v = val;
6920 }
6921 __struct.index = buf.get_u8();
6922 __struct.count = buf.get_u8();
6923 let tmp = buf.get_u8();
6924 __struct.connection_type =
6925 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
6926 enum_type: "EscConnectionType",
6927 value: tmp as u32,
6928 })?;
6929 __struct.info = buf.get_u8();
6930 Ok(__struct)
6931 }
6932 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
6933 let mut __tmp = BytesMut::new(bytes);
6934 #[allow(clippy::absurd_extreme_comparisons)]
6935 #[allow(unused_comparisons)]
6936 if __tmp.remaining() < Self::ENCODED_LEN {
6937 panic!(
6938 "buffer is too small (need {} bytes, but got {})",
6939 Self::ENCODED_LEN,
6940 __tmp.remaining(),
6941 )
6942 }
6943 __tmp.put_u64_le(self.time_usec);
6944 for val in &self.error_count {
6945 __tmp.put_u32_le(*val);
6946 }
6947 __tmp.put_u16_le(self.counter);
6948 for val in &self.failure_flags {
6949 __tmp.put_u16_le(*val);
6950 }
6951 for val in &self.temperature {
6952 __tmp.put_i16_le(*val);
6953 }
6954 __tmp.put_u8(self.index);
6955 __tmp.put_u8(self.count);
6956 __tmp.put_u8(self.connection_type as u8);
6957 __tmp.put_u8(self.info);
6958 if matches!(version, MavlinkVersion::V2) {
6959 let len = __tmp.len();
6960 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
6961 } else {
6962 __tmp.len()
6963 }
6964 }
6965}
6966#[doc = "id: 400"]
6967#[doc = "Play vehicle tone/tune (buzzer). Supersedes message PLAY_TUNE."]
6968#[derive(Debug, Clone, PartialEq)]
6969#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6970#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6971pub struct PLAY_TUNE_V2_DATA {
6972 #[doc = "Tune format"]
6973 pub format: TuneFormat,
6974 #[doc = "System ID"]
6975 pub target_system: u8,
6976 #[doc = "Component ID"]
6977 pub target_component: u8,
6978 #[doc = "Tune definition as a NULL-terminated string."]
6979 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
6980 pub tune: [u8; 248],
6981}
6982impl PLAY_TUNE_V2_DATA {
6983 pub const ENCODED_LEN: usize = 254usize;
6984 pub const DEFAULT: Self = Self {
6985 format: TuneFormat::DEFAULT,
6986 target_system: 0_u8,
6987 target_component: 0_u8,
6988 tune: [0_u8; 248usize],
6989 };
6990 #[cfg(feature = "arbitrary")]
6991 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
6992 use arbitrary::{Arbitrary, Unstructured};
6993 let mut buf = [0u8; 1024];
6994 rng.fill_bytes(&mut buf);
6995 let mut unstructured = Unstructured::new(&buf);
6996 Self::arbitrary(&mut unstructured).unwrap_or_default()
6997 }
6998}
6999impl Default for PLAY_TUNE_V2_DATA {
7000 fn default() -> Self {
7001 Self::DEFAULT.clone()
7002 }
7003}
7004impl MessageData for PLAY_TUNE_V2_DATA {
7005 type Message = MavMessage;
7006 const ID: u32 = 400u32;
7007 const NAME: &'static str = "PLAY_TUNE_V2";
7008 const EXTRA_CRC: u8 = 110u8;
7009 const ENCODED_LEN: usize = 254usize;
7010 fn deser(
7011 _version: MavlinkVersion,
7012 __input: &[u8],
7013 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7014 let avail_len = __input.len();
7015 let mut payload_buf = [0; Self::ENCODED_LEN];
7016 let mut buf = if avail_len < Self::ENCODED_LEN {
7017 payload_buf[0..avail_len].copy_from_slice(__input);
7018 Bytes::new(&payload_buf)
7019 } else {
7020 Bytes::new(__input)
7021 };
7022 let mut __struct = Self::default();
7023 let tmp = buf.get_u32_le();
7024 __struct.format = FromPrimitive::from_u32(tmp).ok_or(
7025 ::mavlink_core::error::ParserError::InvalidEnum {
7026 enum_type: "TuneFormat",
7027 value: tmp as u32,
7028 },
7029 )?;
7030 __struct.target_system = buf.get_u8();
7031 __struct.target_component = buf.get_u8();
7032 for v in &mut __struct.tune {
7033 let val = buf.get_u8();
7034 *v = val;
7035 }
7036 Ok(__struct)
7037 }
7038 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7039 let mut __tmp = BytesMut::new(bytes);
7040 #[allow(clippy::absurd_extreme_comparisons)]
7041 #[allow(unused_comparisons)]
7042 if __tmp.remaining() < Self::ENCODED_LEN {
7043 panic!(
7044 "buffer is too small (need {} bytes, but got {})",
7045 Self::ENCODED_LEN,
7046 __tmp.remaining(),
7047 )
7048 }
7049 __tmp.put_u32_le(self.format as u32);
7050 __tmp.put_u8(self.target_system);
7051 __tmp.put_u8(self.target_component);
7052 for val in &self.tune {
7053 __tmp.put_u8(*val);
7054 }
7055 if matches!(version, MavlinkVersion::V2) {
7056 let len = __tmp.len();
7057 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7058 } else {
7059 __tmp.len()
7060 }
7061 }
7062}
7063#[doc = "id: 36"]
7064#[doc = "Superseded by ACTUATOR_OUTPUT_STATUS. The RAW values of the servo outputs (for RC input from the remote, use the RC_CHANNELS messages). The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%."]
7065#[derive(Debug, Clone, PartialEq)]
7066#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7067#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7068pub struct SERVO_OUTPUT_RAW_DATA {
7069 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
7070 pub time_usec: u32,
7071 #[doc = "Servo output 1 value"]
7072 pub servo1_raw: u16,
7073 #[doc = "Servo output 2 value"]
7074 pub servo2_raw: u16,
7075 #[doc = "Servo output 3 value"]
7076 pub servo3_raw: u16,
7077 #[doc = "Servo output 4 value"]
7078 pub servo4_raw: u16,
7079 #[doc = "Servo output 5 value"]
7080 pub servo5_raw: u16,
7081 #[doc = "Servo output 6 value"]
7082 pub servo6_raw: u16,
7083 #[doc = "Servo output 7 value"]
7084 pub servo7_raw: u16,
7085 #[doc = "Servo output 8 value"]
7086 pub servo8_raw: u16,
7087 #[doc = "Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX."]
7088 pub port: u8,
7089 #[doc = "Servo output 9 value"]
7090 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
7091 pub servo9_raw: u16,
7092 #[doc = "Servo output 10 value"]
7093 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
7094 pub servo10_raw: u16,
7095 #[doc = "Servo output 11 value"]
7096 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
7097 pub servo11_raw: u16,
7098 #[doc = "Servo output 12 value"]
7099 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
7100 pub servo12_raw: u16,
7101 #[doc = "Servo output 13 value"]
7102 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
7103 pub servo13_raw: u16,
7104 #[doc = "Servo output 14 value"]
7105 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
7106 pub servo14_raw: u16,
7107 #[doc = "Servo output 15 value"]
7108 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
7109 pub servo15_raw: u16,
7110 #[doc = "Servo output 16 value"]
7111 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
7112 pub servo16_raw: u16,
7113}
7114impl SERVO_OUTPUT_RAW_DATA {
7115 pub const ENCODED_LEN: usize = 37usize;
7116 pub const DEFAULT: Self = Self {
7117 time_usec: 0_u32,
7118 servo1_raw: 0_u16,
7119 servo2_raw: 0_u16,
7120 servo3_raw: 0_u16,
7121 servo4_raw: 0_u16,
7122 servo5_raw: 0_u16,
7123 servo6_raw: 0_u16,
7124 servo7_raw: 0_u16,
7125 servo8_raw: 0_u16,
7126 port: 0_u8,
7127 servo9_raw: 0_u16,
7128 servo10_raw: 0_u16,
7129 servo11_raw: 0_u16,
7130 servo12_raw: 0_u16,
7131 servo13_raw: 0_u16,
7132 servo14_raw: 0_u16,
7133 servo15_raw: 0_u16,
7134 servo16_raw: 0_u16,
7135 };
7136 #[cfg(feature = "arbitrary")]
7137 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7138 use arbitrary::{Arbitrary, Unstructured};
7139 let mut buf = [0u8; 1024];
7140 rng.fill_bytes(&mut buf);
7141 let mut unstructured = Unstructured::new(&buf);
7142 Self::arbitrary(&mut unstructured).unwrap_or_default()
7143 }
7144}
7145impl Default for SERVO_OUTPUT_RAW_DATA {
7146 fn default() -> Self {
7147 Self::DEFAULT.clone()
7148 }
7149}
7150impl MessageData for SERVO_OUTPUT_RAW_DATA {
7151 type Message = MavMessage;
7152 const ID: u32 = 36u32;
7153 const NAME: &'static str = "SERVO_OUTPUT_RAW";
7154 const EXTRA_CRC: u8 = 222u8;
7155 const ENCODED_LEN: usize = 37usize;
7156 fn deser(
7157 _version: MavlinkVersion,
7158 __input: &[u8],
7159 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7160 let avail_len = __input.len();
7161 let mut payload_buf = [0; Self::ENCODED_LEN];
7162 let mut buf = if avail_len < Self::ENCODED_LEN {
7163 payload_buf[0..avail_len].copy_from_slice(__input);
7164 Bytes::new(&payload_buf)
7165 } else {
7166 Bytes::new(__input)
7167 };
7168 let mut __struct = Self::default();
7169 __struct.time_usec = buf.get_u32_le();
7170 __struct.servo1_raw = buf.get_u16_le();
7171 __struct.servo2_raw = buf.get_u16_le();
7172 __struct.servo3_raw = buf.get_u16_le();
7173 __struct.servo4_raw = buf.get_u16_le();
7174 __struct.servo5_raw = buf.get_u16_le();
7175 __struct.servo6_raw = buf.get_u16_le();
7176 __struct.servo7_raw = buf.get_u16_le();
7177 __struct.servo8_raw = buf.get_u16_le();
7178 __struct.port = buf.get_u8();
7179 __struct.servo9_raw = buf.get_u16_le();
7180 __struct.servo10_raw = buf.get_u16_le();
7181 __struct.servo11_raw = buf.get_u16_le();
7182 __struct.servo12_raw = buf.get_u16_le();
7183 __struct.servo13_raw = buf.get_u16_le();
7184 __struct.servo14_raw = buf.get_u16_le();
7185 __struct.servo15_raw = buf.get_u16_le();
7186 __struct.servo16_raw = buf.get_u16_le();
7187 Ok(__struct)
7188 }
7189 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7190 let mut __tmp = BytesMut::new(bytes);
7191 #[allow(clippy::absurd_extreme_comparisons)]
7192 #[allow(unused_comparisons)]
7193 if __tmp.remaining() < Self::ENCODED_LEN {
7194 panic!(
7195 "buffer is too small (need {} bytes, but got {})",
7196 Self::ENCODED_LEN,
7197 __tmp.remaining(),
7198 )
7199 }
7200 __tmp.put_u32_le(self.time_usec);
7201 __tmp.put_u16_le(self.servo1_raw);
7202 __tmp.put_u16_le(self.servo2_raw);
7203 __tmp.put_u16_le(self.servo3_raw);
7204 __tmp.put_u16_le(self.servo4_raw);
7205 __tmp.put_u16_le(self.servo5_raw);
7206 __tmp.put_u16_le(self.servo6_raw);
7207 __tmp.put_u16_le(self.servo7_raw);
7208 __tmp.put_u16_le(self.servo8_raw);
7209 __tmp.put_u8(self.port);
7210 __tmp.put_u16_le(self.servo9_raw);
7211 __tmp.put_u16_le(self.servo10_raw);
7212 __tmp.put_u16_le(self.servo11_raw);
7213 __tmp.put_u16_le(self.servo12_raw);
7214 __tmp.put_u16_le(self.servo13_raw);
7215 __tmp.put_u16_le(self.servo14_raw);
7216 __tmp.put_u16_le(self.servo15_raw);
7217 __tmp.put_u16_le(self.servo16_raw);
7218 if matches!(version, MavlinkVersion::V2) {
7219 let len = __tmp.len();
7220 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7221 } else {
7222 __tmp.len()
7223 }
7224 }
7225}
7226#[doc = "id: 104"]
7227#[doc = "Global position estimate from a Vicon motion system source."]
7228#[derive(Debug, Clone, PartialEq)]
7229#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7230#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7231pub struct VICON_POSITION_ESTIMATE_DATA {
7232 #[doc = "Timestamp (UNIX time or time since system boot)"]
7233 pub usec: u64,
7234 #[doc = "Global X position"]
7235 pub x: f32,
7236 #[doc = "Global Y position"]
7237 pub y: f32,
7238 #[doc = "Global Z position"]
7239 pub z: f32,
7240 #[doc = "Roll angle"]
7241 pub roll: f32,
7242 #[doc = "Pitch angle"]
7243 pub pitch: f32,
7244 #[doc = "Yaw angle"]
7245 pub yaw: f32,
7246 #[doc = "Row-major representation of 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array."]
7247 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
7248 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
7249 pub covariance: [f32; 21],
7250}
7251impl VICON_POSITION_ESTIMATE_DATA {
7252 pub const ENCODED_LEN: usize = 116usize;
7253 pub const DEFAULT: Self = Self {
7254 usec: 0_u64,
7255 x: 0.0_f32,
7256 y: 0.0_f32,
7257 z: 0.0_f32,
7258 roll: 0.0_f32,
7259 pitch: 0.0_f32,
7260 yaw: 0.0_f32,
7261 covariance: [0.0_f32; 21usize],
7262 };
7263 #[cfg(feature = "arbitrary")]
7264 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7265 use arbitrary::{Arbitrary, Unstructured};
7266 let mut buf = [0u8; 1024];
7267 rng.fill_bytes(&mut buf);
7268 let mut unstructured = Unstructured::new(&buf);
7269 Self::arbitrary(&mut unstructured).unwrap_or_default()
7270 }
7271}
7272impl Default for VICON_POSITION_ESTIMATE_DATA {
7273 fn default() -> Self {
7274 Self::DEFAULT.clone()
7275 }
7276}
7277impl MessageData for VICON_POSITION_ESTIMATE_DATA {
7278 type Message = MavMessage;
7279 const ID: u32 = 104u32;
7280 const NAME: &'static str = "VICON_POSITION_ESTIMATE";
7281 const EXTRA_CRC: u8 = 56u8;
7282 const ENCODED_LEN: usize = 116usize;
7283 fn deser(
7284 _version: MavlinkVersion,
7285 __input: &[u8],
7286 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7287 let avail_len = __input.len();
7288 let mut payload_buf = [0; Self::ENCODED_LEN];
7289 let mut buf = if avail_len < Self::ENCODED_LEN {
7290 payload_buf[0..avail_len].copy_from_slice(__input);
7291 Bytes::new(&payload_buf)
7292 } else {
7293 Bytes::new(__input)
7294 };
7295 let mut __struct = Self::default();
7296 __struct.usec = buf.get_u64_le();
7297 __struct.x = buf.get_f32_le();
7298 __struct.y = buf.get_f32_le();
7299 __struct.z = buf.get_f32_le();
7300 __struct.roll = buf.get_f32_le();
7301 __struct.pitch = buf.get_f32_le();
7302 __struct.yaw = buf.get_f32_le();
7303 for v in &mut __struct.covariance {
7304 let val = buf.get_f32_le();
7305 *v = val;
7306 }
7307 Ok(__struct)
7308 }
7309 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7310 let mut __tmp = BytesMut::new(bytes);
7311 #[allow(clippy::absurd_extreme_comparisons)]
7312 #[allow(unused_comparisons)]
7313 if __tmp.remaining() < Self::ENCODED_LEN {
7314 panic!(
7315 "buffer is too small (need {} bytes, but got {})",
7316 Self::ENCODED_LEN,
7317 __tmp.remaining(),
7318 )
7319 }
7320 __tmp.put_u64_le(self.usec);
7321 __tmp.put_f32_le(self.x);
7322 __tmp.put_f32_le(self.y);
7323 __tmp.put_f32_le(self.z);
7324 __tmp.put_f32_le(self.roll);
7325 __tmp.put_f32_le(self.pitch);
7326 __tmp.put_f32_le(self.yaw);
7327 for val in &self.covariance {
7328 __tmp.put_f32_le(*val);
7329 }
7330 if matches!(version, MavlinkVersion::V2) {
7331 let len = __tmp.len();
7332 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7333 } else {
7334 __tmp.len()
7335 }
7336 }
7337}
7338#[doc = "id: 12903"]
7339#[doc = "Data for filling the OpenDroneID Self ID message. The Self ID Message is an opportunity for the operator to (optionally) declare their identity and purpose of the flight. This message can provide additional information that could reduce the threat profile of a UA (Unmanned Aircraft) flying in a particular area or manner. This message can also be used to provide optional additional clarification in an emergency/remote ID system failure situation."]
7340#[derive(Debug, Clone, PartialEq)]
7341#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7342#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7343pub struct OPEN_DRONE_ID_SELF_ID_DATA {
7344 #[doc = "System ID (0 for broadcast)."]
7345 pub target_system: u8,
7346 #[doc = "Component ID (0 for broadcast)."]
7347 pub target_component: u8,
7348 #[doc = "Only used for drone ID data received from other UAs. See detailed description at <https://mavlink.io/en/services/opendroneid.html>."]
7349 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
7350 pub id_or_mac: [u8; 20],
7351 #[doc = "Indicates the type of the description field."]
7352 pub description_type: MavOdidDescType,
7353 #[doc = "Text description or numeric value expressed as ASCII characters. Shall be filled with nulls in the unused portion of the field."]
7354 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
7355 pub description: [u8; 23],
7356}
7357impl OPEN_DRONE_ID_SELF_ID_DATA {
7358 pub const ENCODED_LEN: usize = 46usize;
7359 pub const DEFAULT: Self = Self {
7360 target_system: 0_u8,
7361 target_component: 0_u8,
7362 id_or_mac: [0_u8; 20usize],
7363 description_type: MavOdidDescType::DEFAULT,
7364 description: [0_u8; 23usize],
7365 };
7366 #[cfg(feature = "arbitrary")]
7367 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7368 use arbitrary::{Arbitrary, Unstructured};
7369 let mut buf = [0u8; 1024];
7370 rng.fill_bytes(&mut buf);
7371 let mut unstructured = Unstructured::new(&buf);
7372 Self::arbitrary(&mut unstructured).unwrap_or_default()
7373 }
7374}
7375impl Default for OPEN_DRONE_ID_SELF_ID_DATA {
7376 fn default() -> Self {
7377 Self::DEFAULT.clone()
7378 }
7379}
7380impl MessageData for OPEN_DRONE_ID_SELF_ID_DATA {
7381 type Message = MavMessage;
7382 const ID: u32 = 12903u32;
7383 const NAME: &'static str = "OPEN_DRONE_ID_SELF_ID";
7384 const EXTRA_CRC: u8 = 249u8;
7385 const ENCODED_LEN: usize = 46usize;
7386 fn deser(
7387 _version: MavlinkVersion,
7388 __input: &[u8],
7389 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7390 let avail_len = __input.len();
7391 let mut payload_buf = [0; Self::ENCODED_LEN];
7392 let mut buf = if avail_len < Self::ENCODED_LEN {
7393 payload_buf[0..avail_len].copy_from_slice(__input);
7394 Bytes::new(&payload_buf)
7395 } else {
7396 Bytes::new(__input)
7397 };
7398 let mut __struct = Self::default();
7399 __struct.target_system = buf.get_u8();
7400 __struct.target_component = buf.get_u8();
7401 for v in &mut __struct.id_or_mac {
7402 let val = buf.get_u8();
7403 *v = val;
7404 }
7405 let tmp = buf.get_u8();
7406 __struct.description_type =
7407 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
7408 enum_type: "MavOdidDescType",
7409 value: tmp as u32,
7410 })?;
7411 for v in &mut __struct.description {
7412 let val = buf.get_u8();
7413 *v = val;
7414 }
7415 Ok(__struct)
7416 }
7417 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7418 let mut __tmp = BytesMut::new(bytes);
7419 #[allow(clippy::absurd_extreme_comparisons)]
7420 #[allow(unused_comparisons)]
7421 if __tmp.remaining() < Self::ENCODED_LEN {
7422 panic!(
7423 "buffer is too small (need {} bytes, but got {})",
7424 Self::ENCODED_LEN,
7425 __tmp.remaining(),
7426 )
7427 }
7428 __tmp.put_u8(self.target_system);
7429 __tmp.put_u8(self.target_component);
7430 for val in &self.id_or_mac {
7431 __tmp.put_u8(*val);
7432 }
7433 __tmp.put_u8(self.description_type as u8);
7434 for val in &self.description {
7435 __tmp.put_u8(*val);
7436 }
7437 if matches!(version, MavlinkVersion::V2) {
7438 let len = __tmp.len();
7439 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7440 } else {
7441 __tmp.len()
7442 }
7443 }
7444}
7445#[doc = "id: 34"]
7446#[doc = "The scaled values of the RC channels received: (-100%) -10000, (0%) 0, (100%) 10000. Channels that are inactive should be set to INT16_MAX."]
7447#[derive(Debug, Clone, PartialEq)]
7448#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7449#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7450pub struct RC_CHANNELS_SCALED_DATA {
7451 #[doc = "Timestamp (time since system boot)."]
7452 pub time_boot_ms: u32,
7453 #[doc = "RC channel 1 value scaled."]
7454 pub chan1_scaled: i16,
7455 #[doc = "RC channel 2 value scaled."]
7456 pub chan2_scaled: i16,
7457 #[doc = "RC channel 3 value scaled."]
7458 pub chan3_scaled: i16,
7459 #[doc = "RC channel 4 value scaled."]
7460 pub chan4_scaled: i16,
7461 #[doc = "RC channel 5 value scaled."]
7462 pub chan5_scaled: i16,
7463 #[doc = "RC channel 6 value scaled."]
7464 pub chan6_scaled: i16,
7465 #[doc = "RC channel 7 value scaled."]
7466 pub chan7_scaled: i16,
7467 #[doc = "RC channel 8 value scaled."]
7468 pub chan8_scaled: i16,
7469 #[doc = "Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX."]
7470 pub port: u8,
7471 #[doc = "Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown."]
7472 pub rssi: u8,
7473}
7474impl RC_CHANNELS_SCALED_DATA {
7475 pub const ENCODED_LEN: usize = 22usize;
7476 pub const DEFAULT: Self = Self {
7477 time_boot_ms: 0_u32,
7478 chan1_scaled: 0_i16,
7479 chan2_scaled: 0_i16,
7480 chan3_scaled: 0_i16,
7481 chan4_scaled: 0_i16,
7482 chan5_scaled: 0_i16,
7483 chan6_scaled: 0_i16,
7484 chan7_scaled: 0_i16,
7485 chan8_scaled: 0_i16,
7486 port: 0_u8,
7487 rssi: 0_u8,
7488 };
7489 #[cfg(feature = "arbitrary")]
7490 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7491 use arbitrary::{Arbitrary, Unstructured};
7492 let mut buf = [0u8; 1024];
7493 rng.fill_bytes(&mut buf);
7494 let mut unstructured = Unstructured::new(&buf);
7495 Self::arbitrary(&mut unstructured).unwrap_or_default()
7496 }
7497}
7498impl Default for RC_CHANNELS_SCALED_DATA {
7499 fn default() -> Self {
7500 Self::DEFAULT.clone()
7501 }
7502}
7503impl MessageData for RC_CHANNELS_SCALED_DATA {
7504 type Message = MavMessage;
7505 const ID: u32 = 34u32;
7506 const NAME: &'static str = "RC_CHANNELS_SCALED";
7507 const EXTRA_CRC: u8 = 237u8;
7508 const ENCODED_LEN: usize = 22usize;
7509 fn deser(
7510 _version: MavlinkVersion,
7511 __input: &[u8],
7512 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7513 let avail_len = __input.len();
7514 let mut payload_buf = [0; Self::ENCODED_LEN];
7515 let mut buf = if avail_len < Self::ENCODED_LEN {
7516 payload_buf[0..avail_len].copy_from_slice(__input);
7517 Bytes::new(&payload_buf)
7518 } else {
7519 Bytes::new(__input)
7520 };
7521 let mut __struct = Self::default();
7522 __struct.time_boot_ms = buf.get_u32_le();
7523 __struct.chan1_scaled = buf.get_i16_le();
7524 __struct.chan2_scaled = buf.get_i16_le();
7525 __struct.chan3_scaled = buf.get_i16_le();
7526 __struct.chan4_scaled = buf.get_i16_le();
7527 __struct.chan5_scaled = buf.get_i16_le();
7528 __struct.chan6_scaled = buf.get_i16_le();
7529 __struct.chan7_scaled = buf.get_i16_le();
7530 __struct.chan8_scaled = buf.get_i16_le();
7531 __struct.port = buf.get_u8();
7532 __struct.rssi = buf.get_u8();
7533 Ok(__struct)
7534 }
7535 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7536 let mut __tmp = BytesMut::new(bytes);
7537 #[allow(clippy::absurd_extreme_comparisons)]
7538 #[allow(unused_comparisons)]
7539 if __tmp.remaining() < Self::ENCODED_LEN {
7540 panic!(
7541 "buffer is too small (need {} bytes, but got {})",
7542 Self::ENCODED_LEN,
7543 __tmp.remaining(),
7544 )
7545 }
7546 __tmp.put_u32_le(self.time_boot_ms);
7547 __tmp.put_i16_le(self.chan1_scaled);
7548 __tmp.put_i16_le(self.chan2_scaled);
7549 __tmp.put_i16_le(self.chan3_scaled);
7550 __tmp.put_i16_le(self.chan4_scaled);
7551 __tmp.put_i16_le(self.chan5_scaled);
7552 __tmp.put_i16_le(self.chan6_scaled);
7553 __tmp.put_i16_le(self.chan7_scaled);
7554 __tmp.put_i16_le(self.chan8_scaled);
7555 __tmp.put_u8(self.port);
7556 __tmp.put_u8(self.rssi);
7557 if matches!(version, MavlinkVersion::V2) {
7558 let len = __tmp.len();
7559 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7560 } else {
7561 __tmp.len()
7562 }
7563 }
7564}
7565#[doc = "id: 270"]
7566#[doc = "Information about the status of a video stream. It may be requested using MAV_CMD_REQUEST_MESSAGE."]
7567#[derive(Debug, Clone, PartialEq)]
7568#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7569#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7570pub struct VIDEO_STREAM_STATUS_DATA {
7571 #[doc = "Frame rate"]
7572 pub framerate: f32,
7573 #[doc = "Bit rate"]
7574 pub bitrate: u32,
7575 #[doc = "Bitmap of stream status flags"]
7576 pub flags: VideoStreamStatusFlags,
7577 #[doc = "Horizontal resolution"]
7578 pub resolution_h: u16,
7579 #[doc = "Vertical resolution"]
7580 pub resolution_v: u16,
7581 #[doc = "Video image rotation clockwise"]
7582 pub rotation: u16,
7583 #[doc = "Horizontal Field of view"]
7584 pub hfov: u16,
7585 #[doc = "Video Stream ID (1 for first, 2 for second, etc.)"]
7586 pub stream_id: u8,
7587 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
7588 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
7589 pub camera_device_id: u8,
7590}
7591impl VIDEO_STREAM_STATUS_DATA {
7592 pub const ENCODED_LEN: usize = 20usize;
7593 pub const DEFAULT: Self = Self {
7594 framerate: 0.0_f32,
7595 bitrate: 0_u32,
7596 flags: VideoStreamStatusFlags::DEFAULT,
7597 resolution_h: 0_u16,
7598 resolution_v: 0_u16,
7599 rotation: 0_u16,
7600 hfov: 0_u16,
7601 stream_id: 0_u8,
7602 camera_device_id: 0_u8,
7603 };
7604 #[cfg(feature = "arbitrary")]
7605 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7606 use arbitrary::{Arbitrary, Unstructured};
7607 let mut buf = [0u8; 1024];
7608 rng.fill_bytes(&mut buf);
7609 let mut unstructured = Unstructured::new(&buf);
7610 Self::arbitrary(&mut unstructured).unwrap_or_default()
7611 }
7612}
7613impl Default for VIDEO_STREAM_STATUS_DATA {
7614 fn default() -> Self {
7615 Self::DEFAULT.clone()
7616 }
7617}
7618impl MessageData for VIDEO_STREAM_STATUS_DATA {
7619 type Message = MavMessage;
7620 const ID: u32 = 270u32;
7621 const NAME: &'static str = "VIDEO_STREAM_STATUS";
7622 const EXTRA_CRC: u8 = 59u8;
7623 const ENCODED_LEN: usize = 20usize;
7624 fn deser(
7625 _version: MavlinkVersion,
7626 __input: &[u8],
7627 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7628 let avail_len = __input.len();
7629 let mut payload_buf = [0; Self::ENCODED_LEN];
7630 let mut buf = if avail_len < Self::ENCODED_LEN {
7631 payload_buf[0..avail_len].copy_from_slice(__input);
7632 Bytes::new(&payload_buf)
7633 } else {
7634 Bytes::new(__input)
7635 };
7636 let mut __struct = Self::default();
7637 __struct.framerate = buf.get_f32_le();
7638 __struct.bitrate = buf.get_u32_le();
7639 let tmp = buf.get_u16_le();
7640 __struct.flags = VideoStreamStatusFlags::from_bits(
7641 tmp & VideoStreamStatusFlags::all().bits(),
7642 )
7643 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
7644 flag_type: "VideoStreamStatusFlags",
7645 value: tmp as u32,
7646 })?;
7647 __struct.resolution_h = buf.get_u16_le();
7648 __struct.resolution_v = buf.get_u16_le();
7649 __struct.rotation = buf.get_u16_le();
7650 __struct.hfov = buf.get_u16_le();
7651 __struct.stream_id = buf.get_u8();
7652 __struct.camera_device_id = buf.get_u8();
7653 Ok(__struct)
7654 }
7655 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7656 let mut __tmp = BytesMut::new(bytes);
7657 #[allow(clippy::absurd_extreme_comparisons)]
7658 #[allow(unused_comparisons)]
7659 if __tmp.remaining() < Self::ENCODED_LEN {
7660 panic!(
7661 "buffer is too small (need {} bytes, but got {})",
7662 Self::ENCODED_LEN,
7663 __tmp.remaining(),
7664 )
7665 }
7666 __tmp.put_f32_le(self.framerate);
7667 __tmp.put_u32_le(self.bitrate);
7668 __tmp.put_u16_le(self.flags.bits());
7669 __tmp.put_u16_le(self.resolution_h);
7670 __tmp.put_u16_le(self.resolution_v);
7671 __tmp.put_u16_le(self.rotation);
7672 __tmp.put_u16_le(self.hfov);
7673 __tmp.put_u8(self.stream_id);
7674 __tmp.put_u8(self.camera_device_id);
7675 if matches!(version, MavlinkVersion::V2) {
7676 let len = __tmp.len();
7677 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7678 } else {
7679 __tmp.len()
7680 }
7681 }
7682}
7683#[doc = "id: 103"]
7684#[doc = "Speed estimate from a vision source."]
7685#[derive(Debug, Clone, PartialEq)]
7686#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7687#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7688pub struct VISION_SPEED_ESTIMATE_DATA {
7689 #[doc = "Timestamp (UNIX time or time since system boot)"]
7690 pub usec: u64,
7691 #[doc = "Global X speed"]
7692 pub x: f32,
7693 #[doc = "Global Y speed"]
7694 pub y: f32,
7695 #[doc = "Global Z speed"]
7696 pub z: f32,
7697 #[doc = "Row-major representation of 3x3 linear velocity covariance matrix (states: vx, vy, vz; 1st three entries - 1st row, etc.). If unknown, assign NaN value to first element in the array."]
7698 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
7699 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
7700 pub covariance: [f32; 9],
7701 #[doc = "Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps."]
7702 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
7703 pub reset_counter: u8,
7704}
7705impl VISION_SPEED_ESTIMATE_DATA {
7706 pub const ENCODED_LEN: usize = 57usize;
7707 pub const DEFAULT: Self = Self {
7708 usec: 0_u64,
7709 x: 0.0_f32,
7710 y: 0.0_f32,
7711 z: 0.0_f32,
7712 covariance: [0.0_f32; 9usize],
7713 reset_counter: 0_u8,
7714 };
7715 #[cfg(feature = "arbitrary")]
7716 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7717 use arbitrary::{Arbitrary, Unstructured};
7718 let mut buf = [0u8; 1024];
7719 rng.fill_bytes(&mut buf);
7720 let mut unstructured = Unstructured::new(&buf);
7721 Self::arbitrary(&mut unstructured).unwrap_or_default()
7722 }
7723}
7724impl Default for VISION_SPEED_ESTIMATE_DATA {
7725 fn default() -> Self {
7726 Self::DEFAULT.clone()
7727 }
7728}
7729impl MessageData for VISION_SPEED_ESTIMATE_DATA {
7730 type Message = MavMessage;
7731 const ID: u32 = 103u32;
7732 const NAME: &'static str = "VISION_SPEED_ESTIMATE";
7733 const EXTRA_CRC: u8 = 208u8;
7734 const ENCODED_LEN: usize = 57usize;
7735 fn deser(
7736 _version: MavlinkVersion,
7737 __input: &[u8],
7738 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7739 let avail_len = __input.len();
7740 let mut payload_buf = [0; Self::ENCODED_LEN];
7741 let mut buf = if avail_len < Self::ENCODED_LEN {
7742 payload_buf[0..avail_len].copy_from_slice(__input);
7743 Bytes::new(&payload_buf)
7744 } else {
7745 Bytes::new(__input)
7746 };
7747 let mut __struct = Self::default();
7748 __struct.usec = buf.get_u64_le();
7749 __struct.x = buf.get_f32_le();
7750 __struct.y = buf.get_f32_le();
7751 __struct.z = buf.get_f32_le();
7752 for v in &mut __struct.covariance {
7753 let val = buf.get_f32_le();
7754 *v = val;
7755 }
7756 __struct.reset_counter = buf.get_u8();
7757 Ok(__struct)
7758 }
7759 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7760 let mut __tmp = BytesMut::new(bytes);
7761 #[allow(clippy::absurd_extreme_comparisons)]
7762 #[allow(unused_comparisons)]
7763 if __tmp.remaining() < Self::ENCODED_LEN {
7764 panic!(
7765 "buffer is too small (need {} bytes, but got {})",
7766 Self::ENCODED_LEN,
7767 __tmp.remaining(),
7768 )
7769 }
7770 __tmp.put_u64_le(self.usec);
7771 __tmp.put_f32_le(self.x);
7772 __tmp.put_f32_le(self.y);
7773 __tmp.put_f32_le(self.z);
7774 for val in &self.covariance {
7775 __tmp.put_f32_le(*val);
7776 }
7777 __tmp.put_u8(self.reset_counter);
7778 if matches!(version, MavlinkVersion::V2) {
7779 let len = __tmp.len();
7780 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7781 } else {
7782 __tmp.len()
7783 }
7784 }
7785}
7786#[doc = "id: 231"]
7787#[doc = "Wind estimate from vehicle. Note that despite the name, this message does not actually contain any covariances but instead variability and accuracy fields in terms of standard deviation (1-STD)."]
7788#[derive(Debug, Clone, PartialEq)]
7789#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7790#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7791pub struct WIND_COV_DATA {
7792 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
7793 pub time_usec: u64,
7794 #[doc = "Wind in North (NED) direction (NAN if unknown)"]
7795 pub wind_x: f32,
7796 #[doc = "Wind in East (NED) direction (NAN if unknown)"]
7797 pub wind_y: f32,
7798 #[doc = "Wind in down (NED) direction (NAN if unknown)"]
7799 pub wind_z: f32,
7800 #[doc = "Variability of wind in XY, 1-STD estimated from a 1 Hz lowpassed wind estimate (NAN if unknown)"]
7801 pub var_horiz: f32,
7802 #[doc = "Variability of wind in Z, 1-STD estimated from a 1 Hz lowpassed wind estimate (NAN if unknown)"]
7803 pub var_vert: f32,
7804 #[doc = "Altitude (MSL) that this measurement was taken at (NAN if unknown)"]
7805 pub wind_alt: f32,
7806 #[doc = "Horizontal speed 1-STD accuracy (0 if unknown)"]
7807 pub horiz_accuracy: f32,
7808 #[doc = "Vertical speed 1-STD accuracy (0 if unknown)"]
7809 pub vert_accuracy: f32,
7810}
7811impl WIND_COV_DATA {
7812 pub const ENCODED_LEN: usize = 40usize;
7813 pub const DEFAULT: Self = Self {
7814 time_usec: 0_u64,
7815 wind_x: 0.0_f32,
7816 wind_y: 0.0_f32,
7817 wind_z: 0.0_f32,
7818 var_horiz: 0.0_f32,
7819 var_vert: 0.0_f32,
7820 wind_alt: 0.0_f32,
7821 horiz_accuracy: 0.0_f32,
7822 vert_accuracy: 0.0_f32,
7823 };
7824 #[cfg(feature = "arbitrary")]
7825 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7826 use arbitrary::{Arbitrary, Unstructured};
7827 let mut buf = [0u8; 1024];
7828 rng.fill_bytes(&mut buf);
7829 let mut unstructured = Unstructured::new(&buf);
7830 Self::arbitrary(&mut unstructured).unwrap_or_default()
7831 }
7832}
7833impl Default for WIND_COV_DATA {
7834 fn default() -> Self {
7835 Self::DEFAULT.clone()
7836 }
7837}
7838impl MessageData for WIND_COV_DATA {
7839 type Message = MavMessage;
7840 const ID: u32 = 231u32;
7841 const NAME: &'static str = "WIND_COV";
7842 const EXTRA_CRC: u8 = 105u8;
7843 const ENCODED_LEN: usize = 40usize;
7844 fn deser(
7845 _version: MavlinkVersion,
7846 __input: &[u8],
7847 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7848 let avail_len = __input.len();
7849 let mut payload_buf = [0; Self::ENCODED_LEN];
7850 let mut buf = if avail_len < Self::ENCODED_LEN {
7851 payload_buf[0..avail_len].copy_from_slice(__input);
7852 Bytes::new(&payload_buf)
7853 } else {
7854 Bytes::new(__input)
7855 };
7856 let mut __struct = Self::default();
7857 __struct.time_usec = buf.get_u64_le();
7858 __struct.wind_x = buf.get_f32_le();
7859 __struct.wind_y = buf.get_f32_le();
7860 __struct.wind_z = buf.get_f32_le();
7861 __struct.var_horiz = buf.get_f32_le();
7862 __struct.var_vert = buf.get_f32_le();
7863 __struct.wind_alt = buf.get_f32_le();
7864 __struct.horiz_accuracy = buf.get_f32_le();
7865 __struct.vert_accuracy = buf.get_f32_le();
7866 Ok(__struct)
7867 }
7868 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7869 let mut __tmp = BytesMut::new(bytes);
7870 #[allow(clippy::absurd_extreme_comparisons)]
7871 #[allow(unused_comparisons)]
7872 if __tmp.remaining() < Self::ENCODED_LEN {
7873 panic!(
7874 "buffer is too small (need {} bytes, but got {})",
7875 Self::ENCODED_LEN,
7876 __tmp.remaining(),
7877 )
7878 }
7879 __tmp.put_u64_le(self.time_usec);
7880 __tmp.put_f32_le(self.wind_x);
7881 __tmp.put_f32_le(self.wind_y);
7882 __tmp.put_f32_le(self.wind_z);
7883 __tmp.put_f32_le(self.var_horiz);
7884 __tmp.put_f32_le(self.var_vert);
7885 __tmp.put_f32_le(self.wind_alt);
7886 __tmp.put_f32_le(self.horiz_accuracy);
7887 __tmp.put_f32_le(self.vert_accuracy);
7888 if matches!(version, MavlinkVersion::V2) {
7889 let len = __tmp.len();
7890 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7891 } else {
7892 __tmp.len()
7893 }
7894 }
7895}
7896#[doc = "id: 26"]
7897#[doc = "The RAW IMU readings for the usual 9DOF sensor setup. This message should contain the scaled values to the described units."]
7898#[derive(Debug, Clone, PartialEq)]
7899#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7900#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7901pub struct SCALED_IMU_DATA {
7902 #[doc = "Timestamp (time since system boot)."]
7903 pub time_boot_ms: u32,
7904 #[doc = "X acceleration"]
7905 pub xacc: i16,
7906 #[doc = "Y acceleration"]
7907 pub yacc: i16,
7908 #[doc = "Z acceleration"]
7909 pub zacc: i16,
7910 #[doc = "Angular speed around X axis"]
7911 pub xgyro: i16,
7912 #[doc = "Angular speed around Y axis"]
7913 pub ygyro: i16,
7914 #[doc = "Angular speed around Z axis"]
7915 pub zgyro: i16,
7916 #[doc = "X Magnetic field"]
7917 pub xmag: i16,
7918 #[doc = "Y Magnetic field"]
7919 pub ymag: i16,
7920 #[doc = "Z Magnetic field"]
7921 pub zmag: i16,
7922 #[doc = "Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C)."]
7923 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
7924 pub temperature: i16,
7925}
7926impl SCALED_IMU_DATA {
7927 pub const ENCODED_LEN: usize = 24usize;
7928 pub const DEFAULT: Self = Self {
7929 time_boot_ms: 0_u32,
7930 xacc: 0_i16,
7931 yacc: 0_i16,
7932 zacc: 0_i16,
7933 xgyro: 0_i16,
7934 ygyro: 0_i16,
7935 zgyro: 0_i16,
7936 xmag: 0_i16,
7937 ymag: 0_i16,
7938 zmag: 0_i16,
7939 temperature: 0_i16,
7940 };
7941 #[cfg(feature = "arbitrary")]
7942 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7943 use arbitrary::{Arbitrary, Unstructured};
7944 let mut buf = [0u8; 1024];
7945 rng.fill_bytes(&mut buf);
7946 let mut unstructured = Unstructured::new(&buf);
7947 Self::arbitrary(&mut unstructured).unwrap_or_default()
7948 }
7949}
7950impl Default for SCALED_IMU_DATA {
7951 fn default() -> Self {
7952 Self::DEFAULT.clone()
7953 }
7954}
7955impl MessageData for SCALED_IMU_DATA {
7956 type Message = MavMessage;
7957 const ID: u32 = 26u32;
7958 const NAME: &'static str = "SCALED_IMU";
7959 const EXTRA_CRC: u8 = 170u8;
7960 const ENCODED_LEN: usize = 24usize;
7961 fn deser(
7962 _version: MavlinkVersion,
7963 __input: &[u8],
7964 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7965 let avail_len = __input.len();
7966 let mut payload_buf = [0; Self::ENCODED_LEN];
7967 let mut buf = if avail_len < Self::ENCODED_LEN {
7968 payload_buf[0..avail_len].copy_from_slice(__input);
7969 Bytes::new(&payload_buf)
7970 } else {
7971 Bytes::new(__input)
7972 };
7973 let mut __struct = Self::default();
7974 __struct.time_boot_ms = buf.get_u32_le();
7975 __struct.xacc = buf.get_i16_le();
7976 __struct.yacc = buf.get_i16_le();
7977 __struct.zacc = buf.get_i16_le();
7978 __struct.xgyro = buf.get_i16_le();
7979 __struct.ygyro = buf.get_i16_le();
7980 __struct.zgyro = buf.get_i16_le();
7981 __struct.xmag = buf.get_i16_le();
7982 __struct.ymag = buf.get_i16_le();
7983 __struct.zmag = buf.get_i16_le();
7984 __struct.temperature = buf.get_i16_le();
7985 Ok(__struct)
7986 }
7987 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7988 let mut __tmp = BytesMut::new(bytes);
7989 #[allow(clippy::absurd_extreme_comparisons)]
7990 #[allow(unused_comparisons)]
7991 if __tmp.remaining() < Self::ENCODED_LEN {
7992 panic!(
7993 "buffer is too small (need {} bytes, but got {})",
7994 Self::ENCODED_LEN,
7995 __tmp.remaining(),
7996 )
7997 }
7998 __tmp.put_u32_le(self.time_boot_ms);
7999 __tmp.put_i16_le(self.xacc);
8000 __tmp.put_i16_le(self.yacc);
8001 __tmp.put_i16_le(self.zacc);
8002 __tmp.put_i16_le(self.xgyro);
8003 __tmp.put_i16_le(self.ygyro);
8004 __tmp.put_i16_le(self.zgyro);
8005 __tmp.put_i16_le(self.xmag);
8006 __tmp.put_i16_le(self.ymag);
8007 __tmp.put_i16_le(self.zmag);
8008 __tmp.put_i16_le(self.temperature);
8009 if matches!(version, MavlinkVersion::V2) {
8010 let len = __tmp.len();
8011 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
8012 } else {
8013 __tmp.len()
8014 }
8015 }
8016}
8017#[doc = "id: 360"]
8018#[doc = "Vehicle status report that is sent out while orbit execution is in progress (see MAV_CMD_DO_ORBIT)."]
8019#[derive(Debug, Clone, PartialEq)]
8020#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
8021#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
8022pub struct ORBIT_EXECUTION_STATUS_DATA {
8023 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
8024 pub time_usec: u64,
8025 #[doc = "Radius of the orbit circle. Positive values orbit clockwise, negative values orbit counter-clockwise."]
8026 pub radius: f32,
8027 #[doc = "X coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7."]
8028 pub x: i32,
8029 #[doc = "Y coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7."]
8030 pub y: i32,
8031 #[doc = "Altitude of center point. Coordinate system depends on frame field."]
8032 pub z: f32,
8033 #[doc = "The coordinate system of the fields: x, y, z."]
8034 pub frame: MavFrame,
8035}
8036impl ORBIT_EXECUTION_STATUS_DATA {
8037 pub const ENCODED_LEN: usize = 25usize;
8038 pub const DEFAULT: Self = Self {
8039 time_usec: 0_u64,
8040 radius: 0.0_f32,
8041 x: 0_i32,
8042 y: 0_i32,
8043 z: 0.0_f32,
8044 frame: MavFrame::DEFAULT,
8045 };
8046 #[cfg(feature = "arbitrary")]
8047 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
8048 use arbitrary::{Arbitrary, Unstructured};
8049 let mut buf = [0u8; 1024];
8050 rng.fill_bytes(&mut buf);
8051 let mut unstructured = Unstructured::new(&buf);
8052 Self::arbitrary(&mut unstructured).unwrap_or_default()
8053 }
8054}
8055impl Default for ORBIT_EXECUTION_STATUS_DATA {
8056 fn default() -> Self {
8057 Self::DEFAULT.clone()
8058 }
8059}
8060impl MessageData for ORBIT_EXECUTION_STATUS_DATA {
8061 type Message = MavMessage;
8062 const ID: u32 = 360u32;
8063 const NAME: &'static str = "ORBIT_EXECUTION_STATUS";
8064 const EXTRA_CRC: u8 = 11u8;
8065 const ENCODED_LEN: usize = 25usize;
8066 fn deser(
8067 _version: MavlinkVersion,
8068 __input: &[u8],
8069 ) -> Result<Self, ::mavlink_core::error::ParserError> {
8070 let avail_len = __input.len();
8071 let mut payload_buf = [0; Self::ENCODED_LEN];
8072 let mut buf = if avail_len < Self::ENCODED_LEN {
8073 payload_buf[0..avail_len].copy_from_slice(__input);
8074 Bytes::new(&payload_buf)
8075 } else {
8076 Bytes::new(__input)
8077 };
8078 let mut __struct = Self::default();
8079 __struct.time_usec = buf.get_u64_le();
8080 __struct.radius = buf.get_f32_le();
8081 __struct.x = buf.get_i32_le();
8082 __struct.y = buf.get_i32_le();
8083 __struct.z = buf.get_f32_le();
8084 let tmp = buf.get_u8();
8085 __struct.frame =
8086 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
8087 enum_type: "MavFrame",
8088 value: tmp as u32,
8089 })?;
8090 Ok(__struct)
8091 }
8092 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
8093 let mut __tmp = BytesMut::new(bytes);
8094 #[allow(clippy::absurd_extreme_comparisons)]
8095 #[allow(unused_comparisons)]
8096 if __tmp.remaining() < Self::ENCODED_LEN {
8097 panic!(
8098 "buffer is too small (need {} bytes, but got {})",
8099 Self::ENCODED_LEN,
8100 __tmp.remaining(),
8101 )
8102 }
8103 __tmp.put_u64_le(self.time_usec);
8104 __tmp.put_f32_le(self.radius);
8105 __tmp.put_i32_le(self.x);
8106 __tmp.put_i32_le(self.y);
8107 __tmp.put_f32_le(self.z);
8108 __tmp.put_u8(self.frame as u8);
8109 if matches!(version, MavlinkVersion::V2) {
8110 let len = __tmp.len();
8111 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
8112 } else {
8113 __tmp.len()
8114 }
8115 }
8116}
8117#[doc = "id: 136"]
8118#[doc = "Streamed from drone to report progress of terrain map download (initiated by TERRAIN_REQUEST), or sent as a response to a TERRAIN_CHECK request. See terrain protocol docs: <https://mavlink.io/en/services/terrain.html>."]
8119#[derive(Debug, Clone, PartialEq)]
8120#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
8121#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
8122pub struct TERRAIN_REPORT_DATA {
8123 #[doc = "Latitude"]
8124 pub lat: i32,
8125 #[doc = "Longitude"]
8126 pub lon: i32,
8127 #[doc = "Terrain height MSL"]
8128 pub terrain_height: f32,
8129 #[doc = "Current vehicle height above lat/lon terrain height"]
8130 pub current_height: f32,
8131 #[doc = "grid spacing (zero if terrain at this location unavailable)"]
8132 pub spacing: u16,
8133 #[doc = "Number of 4x4 terrain blocks waiting to be received or read from disk"]
8134 pub pending: u16,
8135 #[doc = "Number of 4x4 terrain blocks in memory"]
8136 pub loaded: u16,
8137}
8138impl TERRAIN_REPORT_DATA {
8139 pub const ENCODED_LEN: usize = 22usize;
8140 pub const DEFAULT: Self = Self {
8141 lat: 0_i32,
8142 lon: 0_i32,
8143 terrain_height: 0.0_f32,
8144 current_height: 0.0_f32,
8145 spacing: 0_u16,
8146 pending: 0_u16,
8147 loaded: 0_u16,
8148 };
8149 #[cfg(feature = "arbitrary")]
8150 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
8151 use arbitrary::{Arbitrary, Unstructured};
8152 let mut buf = [0u8; 1024];
8153 rng.fill_bytes(&mut buf);
8154 let mut unstructured = Unstructured::new(&buf);
8155 Self::arbitrary(&mut unstructured).unwrap_or_default()
8156 }
8157}
8158impl Default for TERRAIN_REPORT_DATA {
8159 fn default() -> Self {
8160 Self::DEFAULT.clone()
8161 }
8162}
8163impl MessageData for TERRAIN_REPORT_DATA {
8164 type Message = MavMessage;
8165 const ID: u32 = 136u32;
8166 const NAME: &'static str = "TERRAIN_REPORT";
8167 const EXTRA_CRC: u8 = 1u8;
8168 const ENCODED_LEN: usize = 22usize;
8169 fn deser(
8170 _version: MavlinkVersion,
8171 __input: &[u8],
8172 ) -> Result<Self, ::mavlink_core::error::ParserError> {
8173 let avail_len = __input.len();
8174 let mut payload_buf = [0; Self::ENCODED_LEN];
8175 let mut buf = if avail_len < Self::ENCODED_LEN {
8176 payload_buf[0..avail_len].copy_from_slice(__input);
8177 Bytes::new(&payload_buf)
8178 } else {
8179 Bytes::new(__input)
8180 };
8181 let mut __struct = Self::default();
8182 __struct.lat = buf.get_i32_le();
8183 __struct.lon = buf.get_i32_le();
8184 __struct.terrain_height = buf.get_f32_le();
8185 __struct.current_height = buf.get_f32_le();
8186 __struct.spacing = buf.get_u16_le();
8187 __struct.pending = buf.get_u16_le();
8188 __struct.loaded = buf.get_u16_le();
8189 Ok(__struct)
8190 }
8191 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
8192 let mut __tmp = BytesMut::new(bytes);
8193 #[allow(clippy::absurd_extreme_comparisons)]
8194 #[allow(unused_comparisons)]
8195 if __tmp.remaining() < Self::ENCODED_LEN {
8196 panic!(
8197 "buffer is too small (need {} bytes, but got {})",
8198 Self::ENCODED_LEN,
8199 __tmp.remaining(),
8200 )
8201 }
8202 __tmp.put_i32_le(self.lat);
8203 __tmp.put_i32_le(self.lon);
8204 __tmp.put_f32_le(self.terrain_height);
8205 __tmp.put_f32_le(self.current_height);
8206 __tmp.put_u16_le(self.spacing);
8207 __tmp.put_u16_le(self.pending);
8208 __tmp.put_u16_le(self.loaded);
8209 if matches!(version, MavlinkVersion::V2) {
8210 let len = __tmp.len();
8211 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
8212 } else {
8213 __tmp.len()
8214 }
8215 }
8216}
8217#[doc = "id: 147"]
8218#[doc = "Battery information. Updates GCS with flight controller battery status. Smart batteries also use this message, but may additionally send BATTERY_INFO."]
8219#[derive(Debug, Clone, PartialEq)]
8220#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
8221#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
8222pub struct BATTERY_STATUS_DATA {
8223 #[doc = "Consumed charge, -1: autopilot does not provide consumption estimate"]
8224 pub current_consumed: i32,
8225 #[doc = "Consumed energy, -1: autopilot does not provide energy consumption estimate"]
8226 pub energy_consumed: i32,
8227 #[doc = "Temperature of the battery. INT16_MAX for unknown temperature."]
8228 pub temperature: i16,
8229 #[doc = "Battery voltage of cells 1 to 10 (see voltages_ext for cells 11-14). Cells in this field above the valid cell count for this battery should have the UINT16_MAX value. If individual cell voltages are unknown or not measured for this battery, then the overall battery voltage should be filled in cell 0, with all others set to UINT16_MAX. If the voltage of the battery is greater than (UINT16_MAX - 1), then cell 0 should be set to (UINT16_MAX - 1), and cell 1 to the remaining voltage. This can be extended to multiple cells if the total voltage is greater than 2 * (UINT16_MAX - 1)."]
8230 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
8231 pub voltages: [u16; 10],
8232 #[doc = "Battery current, -1: autopilot does not measure the current"]
8233 pub current_battery: i16,
8234 #[doc = "Battery ID"]
8235 pub id: u8,
8236 #[doc = "Function of the battery"]
8237 pub battery_function: MavBatteryFunction,
8238 #[doc = "Type (chemistry) of the battery"]
8239 pub mavtype: MavBatteryType,
8240 #[doc = "Remaining battery energy. Values: [0-100], -1: autopilot does not estimate the remaining battery."]
8241 pub battery_remaining: i8,
8242 #[doc = "Remaining battery time, 0: autopilot does not provide remaining battery time estimate"]
8243 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
8244 pub time_remaining: i32,
8245 #[doc = "State for extent of discharge, provided by autopilot for warning or external reactions"]
8246 #[cfg_attr(feature = "serde", serde(default))]
8247 pub charge_state: MavBatteryChargeState,
8248 #[doc = "Battery voltages for cells 11 to 14. Cells above the valid cell count for this battery should have a value of 0, where zero indicates not supported (note, this is different than for the voltages field and allows empty byte truncation). If the measured value is 0 then 1 should be sent instead."]
8249 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
8250 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
8251 pub voltages_ext: [u16; 4],
8252 #[doc = "Battery mode. Default (0) is that battery mode reporting is not supported or battery is in normal-use mode."]
8253 #[cfg_attr(feature = "serde", serde(default))]
8254 pub mode: MavBatteryMode,
8255 #[doc = "Fault/health indications. These should be set when charge_state is MAV_BATTERY_CHARGE_STATE_FAILED or MAV_BATTERY_CHARGE_STATE_UNHEALTHY (if not, fault reporting is not supported)."]
8256 #[cfg_attr(feature = "serde", serde(default))]
8257 pub fault_bitmask: MavBatteryFault,
8258}
8259impl BATTERY_STATUS_DATA {
8260 pub const ENCODED_LEN: usize = 54usize;
8261 pub const DEFAULT: Self = Self {
8262 current_consumed: 0_i32,
8263 energy_consumed: 0_i32,
8264 temperature: 0_i16,
8265 voltages: [0_u16; 10usize],
8266 current_battery: 0_i16,
8267 id: 0_u8,
8268 battery_function: MavBatteryFunction::DEFAULT,
8269 mavtype: MavBatteryType::DEFAULT,
8270 battery_remaining: 0_i8,
8271 time_remaining: 0_i32,
8272 charge_state: MavBatteryChargeState::DEFAULT,
8273 voltages_ext: [0_u16; 4usize],
8274 mode: MavBatteryMode::DEFAULT,
8275 fault_bitmask: MavBatteryFault::DEFAULT,
8276 };
8277 #[cfg(feature = "arbitrary")]
8278 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
8279 use arbitrary::{Arbitrary, Unstructured};
8280 let mut buf = [0u8; 1024];
8281 rng.fill_bytes(&mut buf);
8282 let mut unstructured = Unstructured::new(&buf);
8283 Self::arbitrary(&mut unstructured).unwrap_or_default()
8284 }
8285}
8286impl Default for BATTERY_STATUS_DATA {
8287 fn default() -> Self {
8288 Self::DEFAULT.clone()
8289 }
8290}
8291impl MessageData for BATTERY_STATUS_DATA {
8292 type Message = MavMessage;
8293 const ID: u32 = 147u32;
8294 const NAME: &'static str = "BATTERY_STATUS";
8295 const EXTRA_CRC: u8 = 154u8;
8296 const ENCODED_LEN: usize = 54usize;
8297 fn deser(
8298 _version: MavlinkVersion,
8299 __input: &[u8],
8300 ) -> Result<Self, ::mavlink_core::error::ParserError> {
8301 let avail_len = __input.len();
8302 let mut payload_buf = [0; Self::ENCODED_LEN];
8303 let mut buf = if avail_len < Self::ENCODED_LEN {
8304 payload_buf[0..avail_len].copy_from_slice(__input);
8305 Bytes::new(&payload_buf)
8306 } else {
8307 Bytes::new(__input)
8308 };
8309 let mut __struct = Self::default();
8310 __struct.current_consumed = buf.get_i32_le();
8311 __struct.energy_consumed = buf.get_i32_le();
8312 __struct.temperature = buf.get_i16_le();
8313 for v in &mut __struct.voltages {
8314 let val = buf.get_u16_le();
8315 *v = val;
8316 }
8317 __struct.current_battery = buf.get_i16_le();
8318 __struct.id = buf.get_u8();
8319 let tmp = buf.get_u8();
8320 __struct.battery_function =
8321 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
8322 enum_type: "MavBatteryFunction",
8323 value: tmp as u32,
8324 })?;
8325 let tmp = buf.get_u8();
8326 __struct.mavtype =
8327 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
8328 enum_type: "MavBatteryType",
8329 value: tmp as u32,
8330 })?;
8331 __struct.battery_remaining = buf.get_i8();
8332 __struct.time_remaining = buf.get_i32_le();
8333 let tmp = buf.get_u8();
8334 __struct.charge_state =
8335 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
8336 enum_type: "MavBatteryChargeState",
8337 value: tmp as u32,
8338 })?;
8339 for v in &mut __struct.voltages_ext {
8340 let val = buf.get_u16_le();
8341 *v = val;
8342 }
8343 let tmp = buf.get_u8();
8344 __struct.mode =
8345 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
8346 enum_type: "MavBatteryMode",
8347 value: tmp as u32,
8348 })?;
8349 let tmp = buf.get_u32_le();
8350 __struct.fault_bitmask = MavBatteryFault::from_bits(tmp & MavBatteryFault::all().bits())
8351 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
8352 flag_type: "MavBatteryFault",
8353 value: tmp as u32,
8354 })?;
8355 Ok(__struct)
8356 }
8357 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
8358 let mut __tmp = BytesMut::new(bytes);
8359 #[allow(clippy::absurd_extreme_comparisons)]
8360 #[allow(unused_comparisons)]
8361 if __tmp.remaining() < Self::ENCODED_LEN {
8362 panic!(
8363 "buffer is too small (need {} bytes, but got {})",
8364 Self::ENCODED_LEN,
8365 __tmp.remaining(),
8366 )
8367 }
8368 __tmp.put_i32_le(self.current_consumed);
8369 __tmp.put_i32_le(self.energy_consumed);
8370 __tmp.put_i16_le(self.temperature);
8371 for val in &self.voltages {
8372 __tmp.put_u16_le(*val);
8373 }
8374 __tmp.put_i16_le(self.current_battery);
8375 __tmp.put_u8(self.id);
8376 __tmp.put_u8(self.battery_function as u8);
8377 __tmp.put_u8(self.mavtype as u8);
8378 __tmp.put_i8(self.battery_remaining);
8379 __tmp.put_i32_le(self.time_remaining);
8380 __tmp.put_u8(self.charge_state as u8);
8381 for val in &self.voltages_ext {
8382 __tmp.put_u16_le(*val);
8383 }
8384 __tmp.put_u8(self.mode as u8);
8385 __tmp.put_u32_le(self.fault_bitmask.bits());
8386 if matches!(version, MavlinkVersion::V2) {
8387 let len = __tmp.len();
8388 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
8389 } else {
8390 __tmp.len()
8391 }
8392 }
8393}
8394#[doc = "id: 291"]
8395#[doc = "ESC information for higher rate streaming. Recommended streaming rate is ~10 Hz. Information that changes more slowly is sent in ESC_INFO. It should typically only be streamed on high-bandwidth links (i.e. to a companion computer)."]
8396#[derive(Debug, Clone, PartialEq)]
8397#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
8398#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
8399pub struct ESC_STATUS_DATA {
8400 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number."]
8401 pub time_usec: u64,
8402 #[doc = "Reported motor RPM from each ESC (negative for reverse rotation)."]
8403 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
8404 pub rpm: [i32; 4],
8405 #[doc = "Voltage measured from each ESC."]
8406 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
8407 pub voltage: [f32; 4],
8408 #[doc = "Current measured from each ESC."]
8409 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
8410 pub current: [f32; 4],
8411 #[doc = "Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4."]
8412 pub index: u8,
8413}
8414impl ESC_STATUS_DATA {
8415 pub const ENCODED_LEN: usize = 57usize;
8416 pub const DEFAULT: Self = Self {
8417 time_usec: 0_u64,
8418 rpm: [0_i32; 4usize],
8419 voltage: [0.0_f32; 4usize],
8420 current: [0.0_f32; 4usize],
8421 index: 0_u8,
8422 };
8423 #[cfg(feature = "arbitrary")]
8424 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
8425 use arbitrary::{Arbitrary, Unstructured};
8426 let mut buf = [0u8; 1024];
8427 rng.fill_bytes(&mut buf);
8428 let mut unstructured = Unstructured::new(&buf);
8429 Self::arbitrary(&mut unstructured).unwrap_or_default()
8430 }
8431}
8432impl Default for ESC_STATUS_DATA {
8433 fn default() -> Self {
8434 Self::DEFAULT.clone()
8435 }
8436}
8437impl MessageData for ESC_STATUS_DATA {
8438 type Message = MavMessage;
8439 const ID: u32 = 291u32;
8440 const NAME: &'static str = "ESC_STATUS";
8441 const EXTRA_CRC: u8 = 10u8;
8442 const ENCODED_LEN: usize = 57usize;
8443 fn deser(
8444 _version: MavlinkVersion,
8445 __input: &[u8],
8446 ) -> Result<Self, ::mavlink_core::error::ParserError> {
8447 let avail_len = __input.len();
8448 let mut payload_buf = [0; Self::ENCODED_LEN];
8449 let mut buf = if avail_len < Self::ENCODED_LEN {
8450 payload_buf[0..avail_len].copy_from_slice(__input);
8451 Bytes::new(&payload_buf)
8452 } else {
8453 Bytes::new(__input)
8454 };
8455 let mut __struct = Self::default();
8456 __struct.time_usec = buf.get_u64_le();
8457 for v in &mut __struct.rpm {
8458 let val = buf.get_i32_le();
8459 *v = val;
8460 }
8461 for v in &mut __struct.voltage {
8462 let val = buf.get_f32_le();
8463 *v = val;
8464 }
8465 for v in &mut __struct.current {
8466 let val = buf.get_f32_le();
8467 *v = val;
8468 }
8469 __struct.index = buf.get_u8();
8470 Ok(__struct)
8471 }
8472 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
8473 let mut __tmp = BytesMut::new(bytes);
8474 #[allow(clippy::absurd_extreme_comparisons)]
8475 #[allow(unused_comparisons)]
8476 if __tmp.remaining() < Self::ENCODED_LEN {
8477 panic!(
8478 "buffer is too small (need {} bytes, but got {})",
8479 Self::ENCODED_LEN,
8480 __tmp.remaining(),
8481 )
8482 }
8483 __tmp.put_u64_le(self.time_usec);
8484 for val in &self.rpm {
8485 __tmp.put_i32_le(*val);
8486 }
8487 for val in &self.voltage {
8488 __tmp.put_f32_le(*val);
8489 }
8490 for val in &self.current {
8491 __tmp.put_f32_le(*val);
8492 }
8493 __tmp.put_u8(self.index);
8494 if matches!(version, MavlinkVersion::V2) {
8495 let len = __tmp.len();
8496 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
8497 } else {
8498 __tmp.len()
8499 }
8500 }
8501}
8502#[doc = "id: 129"]
8503#[doc = "The RAW IMU readings for 3rd 9DOF sensor setup. This message should contain the scaled values to the described units."]
8504#[derive(Debug, Clone, PartialEq)]
8505#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
8506#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
8507pub struct SCALED_IMU3_DATA {
8508 #[doc = "Timestamp (time since system boot)."]
8509 pub time_boot_ms: u32,
8510 #[doc = "X acceleration"]
8511 pub xacc: i16,
8512 #[doc = "Y acceleration"]
8513 pub yacc: i16,
8514 #[doc = "Z acceleration"]
8515 pub zacc: i16,
8516 #[doc = "Angular speed around X axis"]
8517 pub xgyro: i16,
8518 #[doc = "Angular speed around Y axis"]
8519 pub ygyro: i16,
8520 #[doc = "Angular speed around Z axis"]
8521 pub zgyro: i16,
8522 #[doc = "X Magnetic field"]
8523 pub xmag: i16,
8524 #[doc = "Y Magnetic field"]
8525 pub ymag: i16,
8526 #[doc = "Z Magnetic field"]
8527 pub zmag: i16,
8528 #[doc = "Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C)."]
8529 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
8530 pub temperature: i16,
8531}
8532impl SCALED_IMU3_DATA {
8533 pub const ENCODED_LEN: usize = 24usize;
8534 pub const DEFAULT: Self = Self {
8535 time_boot_ms: 0_u32,
8536 xacc: 0_i16,
8537 yacc: 0_i16,
8538 zacc: 0_i16,
8539 xgyro: 0_i16,
8540 ygyro: 0_i16,
8541 zgyro: 0_i16,
8542 xmag: 0_i16,
8543 ymag: 0_i16,
8544 zmag: 0_i16,
8545 temperature: 0_i16,
8546 };
8547 #[cfg(feature = "arbitrary")]
8548 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
8549 use arbitrary::{Arbitrary, Unstructured};
8550 let mut buf = [0u8; 1024];
8551 rng.fill_bytes(&mut buf);
8552 let mut unstructured = Unstructured::new(&buf);
8553 Self::arbitrary(&mut unstructured).unwrap_or_default()
8554 }
8555}
8556impl Default for SCALED_IMU3_DATA {
8557 fn default() -> Self {
8558 Self::DEFAULT.clone()
8559 }
8560}
8561impl MessageData for SCALED_IMU3_DATA {
8562 type Message = MavMessage;
8563 const ID: u32 = 129u32;
8564 const NAME: &'static str = "SCALED_IMU3";
8565 const EXTRA_CRC: u8 = 46u8;
8566 const ENCODED_LEN: usize = 24usize;
8567 fn deser(
8568 _version: MavlinkVersion,
8569 __input: &[u8],
8570 ) -> Result<Self, ::mavlink_core::error::ParserError> {
8571 let avail_len = __input.len();
8572 let mut payload_buf = [0; Self::ENCODED_LEN];
8573 let mut buf = if avail_len < Self::ENCODED_LEN {
8574 payload_buf[0..avail_len].copy_from_slice(__input);
8575 Bytes::new(&payload_buf)
8576 } else {
8577 Bytes::new(__input)
8578 };
8579 let mut __struct = Self::default();
8580 __struct.time_boot_ms = buf.get_u32_le();
8581 __struct.xacc = buf.get_i16_le();
8582 __struct.yacc = buf.get_i16_le();
8583 __struct.zacc = buf.get_i16_le();
8584 __struct.xgyro = buf.get_i16_le();
8585 __struct.ygyro = buf.get_i16_le();
8586 __struct.zgyro = buf.get_i16_le();
8587 __struct.xmag = buf.get_i16_le();
8588 __struct.ymag = buf.get_i16_le();
8589 __struct.zmag = buf.get_i16_le();
8590 __struct.temperature = buf.get_i16_le();
8591 Ok(__struct)
8592 }
8593 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
8594 let mut __tmp = BytesMut::new(bytes);
8595 #[allow(clippy::absurd_extreme_comparisons)]
8596 #[allow(unused_comparisons)]
8597 if __tmp.remaining() < Self::ENCODED_LEN {
8598 panic!(
8599 "buffer is too small (need {} bytes, but got {})",
8600 Self::ENCODED_LEN,
8601 __tmp.remaining(),
8602 )
8603 }
8604 __tmp.put_u32_le(self.time_boot_ms);
8605 __tmp.put_i16_le(self.xacc);
8606 __tmp.put_i16_le(self.yacc);
8607 __tmp.put_i16_le(self.zacc);
8608 __tmp.put_i16_le(self.xgyro);
8609 __tmp.put_i16_le(self.ygyro);
8610 __tmp.put_i16_le(self.zgyro);
8611 __tmp.put_i16_le(self.xmag);
8612 __tmp.put_i16_le(self.ymag);
8613 __tmp.put_i16_le(self.zmag);
8614 __tmp.put_i16_le(self.temperature);
8615 if matches!(version, MavlinkVersion::V2) {
8616 let len = __tmp.len();
8617 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
8618 } else {
8619 __tmp.len()
8620 }
8621 }
8622}
8623#[doc = "id: 140"]
8624#[doc = "Set the vehicle attitude and body angular rates."]
8625#[derive(Debug, Clone, PartialEq)]
8626#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
8627#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
8628pub struct ACTUATOR_CONTROL_TARGET_DATA {
8629 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
8630 pub time_usec: u64,
8631 #[doc = "Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs."]
8632 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
8633 pub controls: [f32; 8],
8634 #[doc = "Actuator group. The \"_mlx\" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances."]
8635 pub group_mlx: u8,
8636}
8637impl ACTUATOR_CONTROL_TARGET_DATA {
8638 pub const ENCODED_LEN: usize = 41usize;
8639 pub const DEFAULT: Self = Self {
8640 time_usec: 0_u64,
8641 controls: [0.0_f32; 8usize],
8642 group_mlx: 0_u8,
8643 };
8644 #[cfg(feature = "arbitrary")]
8645 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
8646 use arbitrary::{Arbitrary, Unstructured};
8647 let mut buf = [0u8; 1024];
8648 rng.fill_bytes(&mut buf);
8649 let mut unstructured = Unstructured::new(&buf);
8650 Self::arbitrary(&mut unstructured).unwrap_or_default()
8651 }
8652}
8653impl Default for ACTUATOR_CONTROL_TARGET_DATA {
8654 fn default() -> Self {
8655 Self::DEFAULT.clone()
8656 }
8657}
8658impl MessageData for ACTUATOR_CONTROL_TARGET_DATA {
8659 type Message = MavMessage;
8660 const ID: u32 = 140u32;
8661 const NAME: &'static str = "ACTUATOR_CONTROL_TARGET";
8662 const EXTRA_CRC: u8 = 181u8;
8663 const ENCODED_LEN: usize = 41usize;
8664 fn deser(
8665 _version: MavlinkVersion,
8666 __input: &[u8],
8667 ) -> Result<Self, ::mavlink_core::error::ParserError> {
8668 let avail_len = __input.len();
8669 let mut payload_buf = [0; Self::ENCODED_LEN];
8670 let mut buf = if avail_len < Self::ENCODED_LEN {
8671 payload_buf[0..avail_len].copy_from_slice(__input);
8672 Bytes::new(&payload_buf)
8673 } else {
8674 Bytes::new(__input)
8675 };
8676 let mut __struct = Self::default();
8677 __struct.time_usec = buf.get_u64_le();
8678 for v in &mut __struct.controls {
8679 let val = buf.get_f32_le();
8680 *v = val;
8681 }
8682 __struct.group_mlx = buf.get_u8();
8683 Ok(__struct)
8684 }
8685 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
8686 let mut __tmp = BytesMut::new(bytes);
8687 #[allow(clippy::absurd_extreme_comparisons)]
8688 #[allow(unused_comparisons)]
8689 if __tmp.remaining() < Self::ENCODED_LEN {
8690 panic!(
8691 "buffer is too small (need {} bytes, but got {})",
8692 Self::ENCODED_LEN,
8693 __tmp.remaining(),
8694 )
8695 }
8696 __tmp.put_u64_le(self.time_usec);
8697 for val in &self.controls {
8698 __tmp.put_f32_le(*val);
8699 }
8700 __tmp.put_u8(self.group_mlx);
8701 if matches!(version, MavlinkVersion::V2) {
8702 let len = __tmp.len();
8703 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
8704 } else {
8705 __tmp.len()
8706 }
8707 }
8708}
8709#[doc = "id: 24"]
8710#[doc = "The global position, as returned by the Global Positioning System (GPS). This is NOT the global position estimate of the system, but rather a RAW sensor value. See message GLOBAL_POSITION_INT for the global position estimate."]
8711#[derive(Debug, Clone, PartialEq)]
8712#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
8713#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
8714pub struct GPS_RAW_INT_DATA {
8715 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
8716 pub time_usec: u64,
8717 #[doc = "Latitude (WGS84, EGM96 ellipsoid)"]
8718 pub lat: i32,
8719 #[doc = "Longitude (WGS84, EGM96 ellipsoid)"]
8720 pub lon: i32,
8721 #[doc = "Altitude (MSL). Positive for up. Note that virtually all GPS modules provide the MSL altitude in addition to the WGS84 altitude."]
8722 pub alt: i32,
8723 #[doc = "GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX"]
8724 pub eph: u16,
8725 #[doc = "GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX"]
8726 pub epv: u16,
8727 #[doc = "GPS ground speed. If unknown, set to: UINT16_MAX"]
8728 pub vel: u16,
8729 #[doc = "Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX"]
8730 pub cog: u16,
8731 #[doc = "GPS fix type."]
8732 pub fix_type: GpsFixType,
8733 #[doc = "Number of satellites visible. If unknown, set to UINT8_MAX"]
8734 pub satellites_visible: u8,
8735 #[doc = "Altitude (above WGS84, EGM96 ellipsoid). Positive for up."]
8736 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
8737 pub alt_ellipsoid: i32,
8738 #[doc = "Position uncertainty."]
8739 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
8740 pub h_acc: u32,
8741 #[doc = "Altitude uncertainty."]
8742 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
8743 pub v_acc: u32,
8744 #[doc = "Speed uncertainty."]
8745 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
8746 pub vel_acc: u32,
8747 #[doc = "Heading / track uncertainty"]
8748 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
8749 pub hdg_acc: u32,
8750 #[doc = "Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use UINT16_MAX if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north."]
8751 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
8752 pub yaw: u16,
8753}
8754impl GPS_RAW_INT_DATA {
8755 pub const ENCODED_LEN: usize = 52usize;
8756 pub const DEFAULT: Self = Self {
8757 time_usec: 0_u64,
8758 lat: 0_i32,
8759 lon: 0_i32,
8760 alt: 0_i32,
8761 eph: 0_u16,
8762 epv: 0_u16,
8763 vel: 0_u16,
8764 cog: 0_u16,
8765 fix_type: GpsFixType::DEFAULT,
8766 satellites_visible: 0_u8,
8767 alt_ellipsoid: 0_i32,
8768 h_acc: 0_u32,
8769 v_acc: 0_u32,
8770 vel_acc: 0_u32,
8771 hdg_acc: 0_u32,
8772 yaw: 0_u16,
8773 };
8774 #[cfg(feature = "arbitrary")]
8775 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
8776 use arbitrary::{Arbitrary, Unstructured};
8777 let mut buf = [0u8; 1024];
8778 rng.fill_bytes(&mut buf);
8779 let mut unstructured = Unstructured::new(&buf);
8780 Self::arbitrary(&mut unstructured).unwrap_or_default()
8781 }
8782}
8783impl Default for GPS_RAW_INT_DATA {
8784 fn default() -> Self {
8785 Self::DEFAULT.clone()
8786 }
8787}
8788impl MessageData for GPS_RAW_INT_DATA {
8789 type Message = MavMessage;
8790 const ID: u32 = 24u32;
8791 const NAME: &'static str = "GPS_RAW_INT";
8792 const EXTRA_CRC: u8 = 24u8;
8793 const ENCODED_LEN: usize = 52usize;
8794 fn deser(
8795 _version: MavlinkVersion,
8796 __input: &[u8],
8797 ) -> Result<Self, ::mavlink_core::error::ParserError> {
8798 let avail_len = __input.len();
8799 let mut payload_buf = [0; Self::ENCODED_LEN];
8800 let mut buf = if avail_len < Self::ENCODED_LEN {
8801 payload_buf[0..avail_len].copy_from_slice(__input);
8802 Bytes::new(&payload_buf)
8803 } else {
8804 Bytes::new(__input)
8805 };
8806 let mut __struct = Self::default();
8807 __struct.time_usec = buf.get_u64_le();
8808 __struct.lat = buf.get_i32_le();
8809 __struct.lon = buf.get_i32_le();
8810 __struct.alt = buf.get_i32_le();
8811 __struct.eph = buf.get_u16_le();
8812 __struct.epv = buf.get_u16_le();
8813 __struct.vel = buf.get_u16_le();
8814 __struct.cog = buf.get_u16_le();
8815 let tmp = buf.get_u8();
8816 __struct.fix_type =
8817 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
8818 enum_type: "GpsFixType",
8819 value: tmp as u32,
8820 })?;
8821 __struct.satellites_visible = buf.get_u8();
8822 __struct.alt_ellipsoid = buf.get_i32_le();
8823 __struct.h_acc = buf.get_u32_le();
8824 __struct.v_acc = buf.get_u32_le();
8825 __struct.vel_acc = buf.get_u32_le();
8826 __struct.hdg_acc = buf.get_u32_le();
8827 __struct.yaw = buf.get_u16_le();
8828 Ok(__struct)
8829 }
8830 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
8831 let mut __tmp = BytesMut::new(bytes);
8832 #[allow(clippy::absurd_extreme_comparisons)]
8833 #[allow(unused_comparisons)]
8834 if __tmp.remaining() < Self::ENCODED_LEN {
8835 panic!(
8836 "buffer is too small (need {} bytes, but got {})",
8837 Self::ENCODED_LEN,
8838 __tmp.remaining(),
8839 )
8840 }
8841 __tmp.put_u64_le(self.time_usec);
8842 __tmp.put_i32_le(self.lat);
8843 __tmp.put_i32_le(self.lon);
8844 __tmp.put_i32_le(self.alt);
8845 __tmp.put_u16_le(self.eph);
8846 __tmp.put_u16_le(self.epv);
8847 __tmp.put_u16_le(self.vel);
8848 __tmp.put_u16_le(self.cog);
8849 __tmp.put_u8(self.fix_type as u8);
8850 __tmp.put_u8(self.satellites_visible);
8851 __tmp.put_i32_le(self.alt_ellipsoid);
8852 __tmp.put_u32_le(self.h_acc);
8853 __tmp.put_u32_le(self.v_acc);
8854 __tmp.put_u32_le(self.vel_acc);
8855 __tmp.put_u32_le(self.hdg_acc);
8856 __tmp.put_u16_le(self.yaw);
8857 if matches!(version, MavlinkVersion::V2) {
8858 let len = __tmp.len();
8859 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
8860 } else {
8861 __tmp.len()
8862 }
8863 }
8864}
8865#[doc = "id: 23"]
8866#[doc = "Set a parameter value (write new value to permanent storage). The receiving component should acknowledge the new parameter value by broadcasting a PARAM_VALUE message (broadcasting ensures that multiple GCS all have an up-to-date list of all parameters). If the sending GCS did not receive a PARAM_VALUE within its timeout time, it should re-send the PARAM_SET message. The parameter microservice is documented at <https://mavlink.io/en/services/parameter.html>."]
8867#[derive(Debug, Clone, PartialEq)]
8868#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
8869#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
8870pub struct PARAM_SET_DATA {
8871 #[doc = "Onboard parameter value"]
8872 pub param_value: f32,
8873 #[doc = "System ID"]
8874 pub target_system: u8,
8875 #[doc = "Component ID"]
8876 pub target_component: u8,
8877 #[doc = "Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string"]
8878 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
8879 pub param_id: [u8; 16],
8880 #[doc = "Onboard parameter type."]
8881 pub param_type: MavParamType,
8882}
8883impl PARAM_SET_DATA {
8884 pub const ENCODED_LEN: usize = 23usize;
8885 pub const DEFAULT: Self = Self {
8886 param_value: 0.0_f32,
8887 target_system: 0_u8,
8888 target_component: 0_u8,
8889 param_id: [0_u8; 16usize],
8890 param_type: MavParamType::DEFAULT,
8891 };
8892 #[cfg(feature = "arbitrary")]
8893 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
8894 use arbitrary::{Arbitrary, Unstructured};
8895 let mut buf = [0u8; 1024];
8896 rng.fill_bytes(&mut buf);
8897 let mut unstructured = Unstructured::new(&buf);
8898 Self::arbitrary(&mut unstructured).unwrap_or_default()
8899 }
8900}
8901impl Default for PARAM_SET_DATA {
8902 fn default() -> Self {
8903 Self::DEFAULT.clone()
8904 }
8905}
8906impl MessageData for PARAM_SET_DATA {
8907 type Message = MavMessage;
8908 const ID: u32 = 23u32;
8909 const NAME: &'static str = "PARAM_SET";
8910 const EXTRA_CRC: u8 = 168u8;
8911 const ENCODED_LEN: usize = 23usize;
8912 fn deser(
8913 _version: MavlinkVersion,
8914 __input: &[u8],
8915 ) -> Result<Self, ::mavlink_core::error::ParserError> {
8916 let avail_len = __input.len();
8917 let mut payload_buf = [0; Self::ENCODED_LEN];
8918 let mut buf = if avail_len < Self::ENCODED_LEN {
8919 payload_buf[0..avail_len].copy_from_slice(__input);
8920 Bytes::new(&payload_buf)
8921 } else {
8922 Bytes::new(__input)
8923 };
8924 let mut __struct = Self::default();
8925 __struct.param_value = buf.get_f32_le();
8926 __struct.target_system = buf.get_u8();
8927 __struct.target_component = buf.get_u8();
8928 for v in &mut __struct.param_id {
8929 let val = buf.get_u8();
8930 *v = val;
8931 }
8932 let tmp = buf.get_u8();
8933 __struct.param_type =
8934 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
8935 enum_type: "MavParamType",
8936 value: tmp as u32,
8937 })?;
8938 Ok(__struct)
8939 }
8940 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
8941 let mut __tmp = BytesMut::new(bytes);
8942 #[allow(clippy::absurd_extreme_comparisons)]
8943 #[allow(unused_comparisons)]
8944 if __tmp.remaining() < Self::ENCODED_LEN {
8945 panic!(
8946 "buffer is too small (need {} bytes, but got {})",
8947 Self::ENCODED_LEN,
8948 __tmp.remaining(),
8949 )
8950 }
8951 __tmp.put_f32_le(self.param_value);
8952 __tmp.put_u8(self.target_system);
8953 __tmp.put_u8(self.target_component);
8954 for val in &self.param_id {
8955 __tmp.put_u8(*val);
8956 }
8957 __tmp.put_u8(self.param_type as u8);
8958 if matches!(version, MavlinkVersion::V2) {
8959 let len = __tmp.len();
8960 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
8961 } else {
8962 __tmp.len()
8963 }
8964 }
8965}
8966#[doc = "id: 85"]
8967#[doc = "Reports the current commanded vehicle position, velocity, and acceleration as specified by the autopilot. This should match the commands sent in SET_POSITION_TARGET_LOCAL_NED if the vehicle is being controlled this way."]
8968#[derive(Debug, Clone, PartialEq)]
8969#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
8970#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
8971pub struct POSITION_TARGET_LOCAL_NED_DATA {
8972 #[doc = "Timestamp (time since system boot)."]
8973 pub time_boot_ms: u32,
8974 #[doc = "X Position in NED frame"]
8975 pub x: f32,
8976 #[doc = "Y Position in NED frame"]
8977 pub y: f32,
8978 #[doc = "Z Position in NED frame (note, altitude is negative in NED)"]
8979 pub z: f32,
8980 #[doc = "X velocity in NED frame"]
8981 pub vx: f32,
8982 #[doc = "Y velocity in NED frame"]
8983 pub vy: f32,
8984 #[doc = "Z velocity in NED frame"]
8985 pub vz: f32,
8986 #[doc = "X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
8987 pub afx: f32,
8988 #[doc = "Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
8989 pub afy: f32,
8990 #[doc = "Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
8991 pub afz: f32,
8992 #[doc = "yaw setpoint"]
8993 pub yaw: f32,
8994 #[doc = "yaw rate setpoint"]
8995 pub yaw_rate: f32,
8996 #[doc = "Bitmap to indicate which dimensions should be ignored by the vehicle."]
8997 pub type_mask: PositionTargetTypemask,
8998 #[doc = "Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9"]
8999 pub coordinate_frame: MavFrame,
9000}
9001impl POSITION_TARGET_LOCAL_NED_DATA {
9002 pub const ENCODED_LEN: usize = 51usize;
9003 pub const DEFAULT: Self = Self {
9004 time_boot_ms: 0_u32,
9005 x: 0.0_f32,
9006 y: 0.0_f32,
9007 z: 0.0_f32,
9008 vx: 0.0_f32,
9009 vy: 0.0_f32,
9010 vz: 0.0_f32,
9011 afx: 0.0_f32,
9012 afy: 0.0_f32,
9013 afz: 0.0_f32,
9014 yaw: 0.0_f32,
9015 yaw_rate: 0.0_f32,
9016 type_mask: PositionTargetTypemask::DEFAULT,
9017 coordinate_frame: MavFrame::DEFAULT,
9018 };
9019 #[cfg(feature = "arbitrary")]
9020 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9021 use arbitrary::{Arbitrary, Unstructured};
9022 let mut buf = [0u8; 1024];
9023 rng.fill_bytes(&mut buf);
9024 let mut unstructured = Unstructured::new(&buf);
9025 Self::arbitrary(&mut unstructured).unwrap_or_default()
9026 }
9027}
9028impl Default for POSITION_TARGET_LOCAL_NED_DATA {
9029 fn default() -> Self {
9030 Self::DEFAULT.clone()
9031 }
9032}
9033impl MessageData for POSITION_TARGET_LOCAL_NED_DATA {
9034 type Message = MavMessage;
9035 const ID: u32 = 85u32;
9036 const NAME: &'static str = "POSITION_TARGET_LOCAL_NED";
9037 const EXTRA_CRC: u8 = 140u8;
9038 const ENCODED_LEN: usize = 51usize;
9039 fn deser(
9040 _version: MavlinkVersion,
9041 __input: &[u8],
9042 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9043 let avail_len = __input.len();
9044 let mut payload_buf = [0; Self::ENCODED_LEN];
9045 let mut buf = if avail_len < Self::ENCODED_LEN {
9046 payload_buf[0..avail_len].copy_from_slice(__input);
9047 Bytes::new(&payload_buf)
9048 } else {
9049 Bytes::new(__input)
9050 };
9051 let mut __struct = Self::default();
9052 __struct.time_boot_ms = buf.get_u32_le();
9053 __struct.x = buf.get_f32_le();
9054 __struct.y = buf.get_f32_le();
9055 __struct.z = buf.get_f32_le();
9056 __struct.vx = buf.get_f32_le();
9057 __struct.vy = buf.get_f32_le();
9058 __struct.vz = buf.get_f32_le();
9059 __struct.afx = buf.get_f32_le();
9060 __struct.afy = buf.get_f32_le();
9061 __struct.afz = buf.get_f32_le();
9062 __struct.yaw = buf.get_f32_le();
9063 __struct.yaw_rate = buf.get_f32_le();
9064 let tmp = buf.get_u16_le();
9065 __struct.type_mask = PositionTargetTypemask::from_bits(
9066 tmp & PositionTargetTypemask::all().bits(),
9067 )
9068 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
9069 flag_type: "PositionTargetTypemask",
9070 value: tmp as u32,
9071 })?;
9072 let tmp = buf.get_u8();
9073 __struct.coordinate_frame =
9074 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
9075 enum_type: "MavFrame",
9076 value: tmp as u32,
9077 })?;
9078 Ok(__struct)
9079 }
9080 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
9081 let mut __tmp = BytesMut::new(bytes);
9082 #[allow(clippy::absurd_extreme_comparisons)]
9083 #[allow(unused_comparisons)]
9084 if __tmp.remaining() < Self::ENCODED_LEN {
9085 panic!(
9086 "buffer is too small (need {} bytes, but got {})",
9087 Self::ENCODED_LEN,
9088 __tmp.remaining(),
9089 )
9090 }
9091 __tmp.put_u32_le(self.time_boot_ms);
9092 __tmp.put_f32_le(self.x);
9093 __tmp.put_f32_le(self.y);
9094 __tmp.put_f32_le(self.z);
9095 __tmp.put_f32_le(self.vx);
9096 __tmp.put_f32_le(self.vy);
9097 __tmp.put_f32_le(self.vz);
9098 __tmp.put_f32_le(self.afx);
9099 __tmp.put_f32_le(self.afy);
9100 __tmp.put_f32_le(self.afz);
9101 __tmp.put_f32_le(self.yaw);
9102 __tmp.put_f32_le(self.yaw_rate);
9103 __tmp.put_u16_le(self.type_mask.bits());
9104 __tmp.put_u8(self.coordinate_frame as u8);
9105 if matches!(version, MavlinkVersion::V2) {
9106 let len = __tmp.len();
9107 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
9108 } else {
9109 __tmp.len()
9110 }
9111 }
9112}
9113#[doc = "id: 436"]
9114#[doc = "Get the current mode. This should be emitted on any mode change, and broadcast at low rate (nominally 0.5 Hz). It may be requested using MAV_CMD_REQUEST_MESSAGE. See <https://mavlink.io/en/services/standard_modes.html>."]
9115#[derive(Debug, Clone, PartialEq)]
9116#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9117#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9118pub struct CURRENT_MODE_DATA {
9119 #[doc = "A bitfield for use for autopilot-specific flags"]
9120 pub custom_mode: u32,
9121 #[doc = "The custom_mode of the mode that was last commanded by the user (for example, with MAV_CMD_DO_SET_STANDARD_MODE, MAV_CMD_DO_SET_MODE or via RC). This should usually be the same as custom_mode. It will be different if the vehicle is unable to enter the intended mode, or has left that mode due to a failsafe condition. 0 indicates the intended custom mode is unknown/not supplied"]
9122 pub intended_custom_mode: u32,
9123 #[doc = "Standard mode."]
9124 pub standard_mode: MavStandardMode,
9125}
9126impl CURRENT_MODE_DATA {
9127 pub const ENCODED_LEN: usize = 9usize;
9128 pub const DEFAULT: Self = Self {
9129 custom_mode: 0_u32,
9130 intended_custom_mode: 0_u32,
9131 standard_mode: MavStandardMode::DEFAULT,
9132 };
9133 #[cfg(feature = "arbitrary")]
9134 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9135 use arbitrary::{Arbitrary, Unstructured};
9136 let mut buf = [0u8; 1024];
9137 rng.fill_bytes(&mut buf);
9138 let mut unstructured = Unstructured::new(&buf);
9139 Self::arbitrary(&mut unstructured).unwrap_or_default()
9140 }
9141}
9142impl Default for CURRENT_MODE_DATA {
9143 fn default() -> Self {
9144 Self::DEFAULT.clone()
9145 }
9146}
9147impl MessageData for CURRENT_MODE_DATA {
9148 type Message = MavMessage;
9149 const ID: u32 = 436u32;
9150 const NAME: &'static str = "CURRENT_MODE";
9151 const EXTRA_CRC: u8 = 193u8;
9152 const ENCODED_LEN: usize = 9usize;
9153 fn deser(
9154 _version: MavlinkVersion,
9155 __input: &[u8],
9156 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9157 let avail_len = __input.len();
9158 let mut payload_buf = [0; Self::ENCODED_LEN];
9159 let mut buf = if avail_len < Self::ENCODED_LEN {
9160 payload_buf[0..avail_len].copy_from_slice(__input);
9161 Bytes::new(&payload_buf)
9162 } else {
9163 Bytes::new(__input)
9164 };
9165 let mut __struct = Self::default();
9166 __struct.custom_mode = buf.get_u32_le();
9167 __struct.intended_custom_mode = buf.get_u32_le();
9168 let tmp = buf.get_u8();
9169 __struct.standard_mode =
9170 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
9171 enum_type: "MavStandardMode",
9172 value: tmp as u32,
9173 })?;
9174 Ok(__struct)
9175 }
9176 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
9177 let mut __tmp = BytesMut::new(bytes);
9178 #[allow(clippy::absurd_extreme_comparisons)]
9179 #[allow(unused_comparisons)]
9180 if __tmp.remaining() < Self::ENCODED_LEN {
9181 panic!(
9182 "buffer is too small (need {} bytes, but got {})",
9183 Self::ENCODED_LEN,
9184 __tmp.remaining(),
9185 )
9186 }
9187 __tmp.put_u32_le(self.custom_mode);
9188 __tmp.put_u32_le(self.intended_custom_mode);
9189 __tmp.put_u8(self.standard_mode as u8);
9190 if matches!(version, MavlinkVersion::V2) {
9191 let len = __tmp.len();
9192 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
9193 } else {
9194 __tmp.len()
9195 }
9196 }
9197}
9198#[doc = "id: 301"]
9199#[doc = "The location and information of an AIS vessel."]
9200#[derive(Debug, Clone, PartialEq)]
9201#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9202#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9203pub struct AIS_VESSEL_DATA {
9204 #[doc = "Mobile Marine Service Identifier, 9 decimal digits"]
9205 pub MMSI: u32,
9206 #[doc = "Latitude"]
9207 pub lat: i32,
9208 #[doc = "Longitude"]
9209 pub lon: i32,
9210 #[doc = "Course over ground"]
9211 pub COG: u16,
9212 #[doc = "True heading"]
9213 pub heading: u16,
9214 #[doc = "Speed over ground"]
9215 pub velocity: u16,
9216 #[doc = "Distance from lat/lon location to bow"]
9217 pub dimension_bow: u16,
9218 #[doc = "Distance from lat/lon location to stern"]
9219 pub dimension_stern: u16,
9220 #[doc = "Time since last communication in seconds"]
9221 pub tslc: u16,
9222 #[doc = "Bitmask to indicate various statuses including valid data fields"]
9223 pub flags: AisFlags,
9224 #[doc = "Turn rate"]
9225 pub turn_rate: i8,
9226 #[doc = "Navigational status"]
9227 pub navigational_status: AisNavStatus,
9228 #[doc = "Type of vessels"]
9229 pub mavtype: AisType,
9230 #[doc = "Distance from lat/lon location to port side"]
9231 pub dimension_port: u8,
9232 #[doc = "Distance from lat/lon location to starboard side"]
9233 pub dimension_starboard: u8,
9234 #[doc = "The vessel callsign"]
9235 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
9236 pub callsign: [u8; 7],
9237 #[doc = "The vessel name"]
9238 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
9239 pub name: [u8; 20],
9240}
9241impl AIS_VESSEL_DATA {
9242 pub const ENCODED_LEN: usize = 58usize;
9243 pub const DEFAULT: Self = Self {
9244 MMSI: 0_u32,
9245 lat: 0_i32,
9246 lon: 0_i32,
9247 COG: 0_u16,
9248 heading: 0_u16,
9249 velocity: 0_u16,
9250 dimension_bow: 0_u16,
9251 dimension_stern: 0_u16,
9252 tslc: 0_u16,
9253 flags: AisFlags::DEFAULT,
9254 turn_rate: 0_i8,
9255 navigational_status: AisNavStatus::DEFAULT,
9256 mavtype: AisType::DEFAULT,
9257 dimension_port: 0_u8,
9258 dimension_starboard: 0_u8,
9259 callsign: [0_u8; 7usize],
9260 name: [0_u8; 20usize],
9261 };
9262 #[cfg(feature = "arbitrary")]
9263 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9264 use arbitrary::{Arbitrary, Unstructured};
9265 let mut buf = [0u8; 1024];
9266 rng.fill_bytes(&mut buf);
9267 let mut unstructured = Unstructured::new(&buf);
9268 Self::arbitrary(&mut unstructured).unwrap_or_default()
9269 }
9270}
9271impl Default for AIS_VESSEL_DATA {
9272 fn default() -> Self {
9273 Self::DEFAULT.clone()
9274 }
9275}
9276impl MessageData for AIS_VESSEL_DATA {
9277 type Message = MavMessage;
9278 const ID: u32 = 301u32;
9279 const NAME: &'static str = "AIS_VESSEL";
9280 const EXTRA_CRC: u8 = 243u8;
9281 const ENCODED_LEN: usize = 58usize;
9282 fn deser(
9283 _version: MavlinkVersion,
9284 __input: &[u8],
9285 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9286 let avail_len = __input.len();
9287 let mut payload_buf = [0; Self::ENCODED_LEN];
9288 let mut buf = if avail_len < Self::ENCODED_LEN {
9289 payload_buf[0..avail_len].copy_from_slice(__input);
9290 Bytes::new(&payload_buf)
9291 } else {
9292 Bytes::new(__input)
9293 };
9294 let mut __struct = Self::default();
9295 __struct.MMSI = buf.get_u32_le();
9296 __struct.lat = buf.get_i32_le();
9297 __struct.lon = buf.get_i32_le();
9298 __struct.COG = buf.get_u16_le();
9299 __struct.heading = buf.get_u16_le();
9300 __struct.velocity = buf.get_u16_le();
9301 __struct.dimension_bow = buf.get_u16_le();
9302 __struct.dimension_stern = buf.get_u16_le();
9303 __struct.tslc = buf.get_u16_le();
9304 let tmp = buf.get_u16_le();
9305 __struct.flags = AisFlags::from_bits(tmp & AisFlags::all().bits()).ok_or(
9306 ::mavlink_core::error::ParserError::InvalidFlag {
9307 flag_type: "AisFlags",
9308 value: tmp as u32,
9309 },
9310 )?;
9311 __struct.turn_rate = buf.get_i8();
9312 let tmp = buf.get_u8();
9313 __struct.navigational_status =
9314 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
9315 enum_type: "AisNavStatus",
9316 value: tmp as u32,
9317 })?;
9318 let tmp = buf.get_u8();
9319 __struct.mavtype =
9320 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
9321 enum_type: "AisType",
9322 value: tmp as u32,
9323 })?;
9324 __struct.dimension_port = buf.get_u8();
9325 __struct.dimension_starboard = buf.get_u8();
9326 for v in &mut __struct.callsign {
9327 let val = buf.get_u8();
9328 *v = val;
9329 }
9330 for v in &mut __struct.name {
9331 let val = buf.get_u8();
9332 *v = val;
9333 }
9334 Ok(__struct)
9335 }
9336 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
9337 let mut __tmp = BytesMut::new(bytes);
9338 #[allow(clippy::absurd_extreme_comparisons)]
9339 #[allow(unused_comparisons)]
9340 if __tmp.remaining() < Self::ENCODED_LEN {
9341 panic!(
9342 "buffer is too small (need {} bytes, but got {})",
9343 Self::ENCODED_LEN,
9344 __tmp.remaining(),
9345 )
9346 }
9347 __tmp.put_u32_le(self.MMSI);
9348 __tmp.put_i32_le(self.lat);
9349 __tmp.put_i32_le(self.lon);
9350 __tmp.put_u16_le(self.COG);
9351 __tmp.put_u16_le(self.heading);
9352 __tmp.put_u16_le(self.velocity);
9353 __tmp.put_u16_le(self.dimension_bow);
9354 __tmp.put_u16_le(self.dimension_stern);
9355 __tmp.put_u16_le(self.tslc);
9356 __tmp.put_u16_le(self.flags.bits());
9357 __tmp.put_i8(self.turn_rate);
9358 __tmp.put_u8(self.navigational_status as u8);
9359 __tmp.put_u8(self.mavtype as u8);
9360 __tmp.put_u8(self.dimension_port);
9361 __tmp.put_u8(self.dimension_starboard);
9362 for val in &self.callsign {
9363 __tmp.put_u8(*val);
9364 }
9365 for val in &self.name {
9366 __tmp.put_u8(*val);
9367 }
9368 if matches!(version, MavlinkVersion::V2) {
9369 let len = __tmp.len();
9370 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
9371 } else {
9372 __tmp.len()
9373 }
9374 }
9375}
9376#[doc = "id: 131"]
9377#[doc = "Data packet for images sent using the Image Transmission Protocol: <https://mavlink.io/en/services/image_transmission.html>."]
9378#[derive(Debug, Clone, PartialEq)]
9379#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9380#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9381pub struct ENCAPSULATED_DATA_DATA {
9382 #[doc = "sequence number (starting with 0 on every transmission)"]
9383 pub seqnr: u16,
9384 #[doc = "image data bytes"]
9385 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
9386 pub data: [u8; 253],
9387}
9388impl ENCAPSULATED_DATA_DATA {
9389 pub const ENCODED_LEN: usize = 255usize;
9390 pub const DEFAULT: Self = Self {
9391 seqnr: 0_u16,
9392 data: [0_u8; 253usize],
9393 };
9394 #[cfg(feature = "arbitrary")]
9395 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9396 use arbitrary::{Arbitrary, Unstructured};
9397 let mut buf = [0u8; 1024];
9398 rng.fill_bytes(&mut buf);
9399 let mut unstructured = Unstructured::new(&buf);
9400 Self::arbitrary(&mut unstructured).unwrap_or_default()
9401 }
9402}
9403impl Default for ENCAPSULATED_DATA_DATA {
9404 fn default() -> Self {
9405 Self::DEFAULT.clone()
9406 }
9407}
9408impl MessageData for ENCAPSULATED_DATA_DATA {
9409 type Message = MavMessage;
9410 const ID: u32 = 131u32;
9411 const NAME: &'static str = "ENCAPSULATED_DATA";
9412 const EXTRA_CRC: u8 = 223u8;
9413 const ENCODED_LEN: usize = 255usize;
9414 fn deser(
9415 _version: MavlinkVersion,
9416 __input: &[u8],
9417 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9418 let avail_len = __input.len();
9419 let mut payload_buf = [0; Self::ENCODED_LEN];
9420 let mut buf = if avail_len < Self::ENCODED_LEN {
9421 payload_buf[0..avail_len].copy_from_slice(__input);
9422 Bytes::new(&payload_buf)
9423 } else {
9424 Bytes::new(__input)
9425 };
9426 let mut __struct = Self::default();
9427 __struct.seqnr = buf.get_u16_le();
9428 for v in &mut __struct.data {
9429 let val = buf.get_u8();
9430 *v = val;
9431 }
9432 Ok(__struct)
9433 }
9434 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
9435 let mut __tmp = BytesMut::new(bytes);
9436 #[allow(clippy::absurd_extreme_comparisons)]
9437 #[allow(unused_comparisons)]
9438 if __tmp.remaining() < Self::ENCODED_LEN {
9439 panic!(
9440 "buffer is too small (need {} bytes, but got {})",
9441 Self::ENCODED_LEN,
9442 __tmp.remaining(),
9443 )
9444 }
9445 __tmp.put_u16_le(self.seqnr);
9446 for val in &self.data {
9447 __tmp.put_u8(*val);
9448 }
9449 if matches!(version, MavlinkVersion::V2) {
9450 let len = __tmp.len();
9451 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
9452 } else {
9453 __tmp.len()
9454 }
9455 }
9456}
9457#[doc = "id: 440"]
9458#[doc = "Illuminator status."]
9459#[derive(Debug, Clone, PartialEq)]
9460#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9461#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9462pub struct ILLUMINATOR_STATUS_DATA {
9463 #[doc = "Time since the start-up of the illuminator in ms"]
9464 pub uptime_ms: u32,
9465 #[doc = "Errors"]
9466 pub error_status: IlluminatorErrorFlags,
9467 #[doc = "Illuminator brightness"]
9468 pub brightness: f32,
9469 #[doc = "Illuminator strobing period in seconds"]
9470 pub strobe_period: f32,
9471 #[doc = "Illuminator strobing duty cycle"]
9472 pub strobe_duty_cycle: f32,
9473 #[doc = "Temperature in Celsius"]
9474 pub temp_c: f32,
9475 #[doc = "Minimum strobing period in seconds"]
9476 pub min_strobe_period: f32,
9477 #[doc = "Maximum strobing period in seconds"]
9478 pub max_strobe_period: f32,
9479 #[doc = "0: Illuminators OFF, 1: Illuminators ON"]
9480 pub enable: u8,
9481 #[doc = "Supported illuminator modes"]
9482 pub mode_bitmask: IlluminatorMode,
9483 #[doc = "Illuminator mode"]
9484 pub mode: IlluminatorMode,
9485}
9486impl ILLUMINATOR_STATUS_DATA {
9487 pub const ENCODED_LEN: usize = 35usize;
9488 pub const DEFAULT: Self = Self {
9489 uptime_ms: 0_u32,
9490 error_status: IlluminatorErrorFlags::DEFAULT,
9491 brightness: 0.0_f32,
9492 strobe_period: 0.0_f32,
9493 strobe_duty_cycle: 0.0_f32,
9494 temp_c: 0.0_f32,
9495 min_strobe_period: 0.0_f32,
9496 max_strobe_period: 0.0_f32,
9497 enable: 0_u8,
9498 mode_bitmask: IlluminatorMode::DEFAULT,
9499 mode: IlluminatorMode::DEFAULT,
9500 };
9501 #[cfg(feature = "arbitrary")]
9502 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9503 use arbitrary::{Arbitrary, Unstructured};
9504 let mut buf = [0u8; 1024];
9505 rng.fill_bytes(&mut buf);
9506 let mut unstructured = Unstructured::new(&buf);
9507 Self::arbitrary(&mut unstructured).unwrap_or_default()
9508 }
9509}
9510impl Default for ILLUMINATOR_STATUS_DATA {
9511 fn default() -> Self {
9512 Self::DEFAULT.clone()
9513 }
9514}
9515impl MessageData for ILLUMINATOR_STATUS_DATA {
9516 type Message = MavMessage;
9517 const ID: u32 = 440u32;
9518 const NAME: &'static str = "ILLUMINATOR_STATUS";
9519 const EXTRA_CRC: u8 = 66u8;
9520 const ENCODED_LEN: usize = 35usize;
9521 fn deser(
9522 _version: MavlinkVersion,
9523 __input: &[u8],
9524 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9525 let avail_len = __input.len();
9526 let mut payload_buf = [0; Self::ENCODED_LEN];
9527 let mut buf = if avail_len < Self::ENCODED_LEN {
9528 payload_buf[0..avail_len].copy_from_slice(__input);
9529 Bytes::new(&payload_buf)
9530 } else {
9531 Bytes::new(__input)
9532 };
9533 let mut __struct = Self::default();
9534 __struct.uptime_ms = buf.get_u32_le();
9535 let tmp = buf.get_u32_le();
9536 __struct.error_status = IlluminatorErrorFlags::from_bits(
9537 tmp & IlluminatorErrorFlags::all().bits(),
9538 )
9539 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
9540 flag_type: "IlluminatorErrorFlags",
9541 value: tmp as u32,
9542 })?;
9543 __struct.brightness = buf.get_f32_le();
9544 __struct.strobe_period = buf.get_f32_le();
9545 __struct.strobe_duty_cycle = buf.get_f32_le();
9546 __struct.temp_c = buf.get_f32_le();
9547 __struct.min_strobe_period = buf.get_f32_le();
9548 __struct.max_strobe_period = buf.get_f32_le();
9549 __struct.enable = buf.get_u8();
9550 let tmp = buf.get_u8();
9551 __struct.mode_bitmask =
9552 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
9553 enum_type: "IlluminatorMode",
9554 value: tmp as u32,
9555 })?;
9556 let tmp = buf.get_u8();
9557 __struct.mode =
9558 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
9559 enum_type: "IlluminatorMode",
9560 value: tmp as u32,
9561 })?;
9562 Ok(__struct)
9563 }
9564 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
9565 let mut __tmp = BytesMut::new(bytes);
9566 #[allow(clippy::absurd_extreme_comparisons)]
9567 #[allow(unused_comparisons)]
9568 if __tmp.remaining() < Self::ENCODED_LEN {
9569 panic!(
9570 "buffer is too small (need {} bytes, but got {})",
9571 Self::ENCODED_LEN,
9572 __tmp.remaining(),
9573 )
9574 }
9575 __tmp.put_u32_le(self.uptime_ms);
9576 __tmp.put_u32_le(self.error_status.bits());
9577 __tmp.put_f32_le(self.brightness);
9578 __tmp.put_f32_le(self.strobe_period);
9579 __tmp.put_f32_le(self.strobe_duty_cycle);
9580 __tmp.put_f32_le(self.temp_c);
9581 __tmp.put_f32_le(self.min_strobe_period);
9582 __tmp.put_f32_le(self.max_strobe_period);
9583 __tmp.put_u8(self.enable);
9584 __tmp.put_u8(self.mode_bitmask as u8);
9585 __tmp.put_u8(self.mode as u8);
9586 if matches!(version, MavlinkVersion::V2) {
9587 let len = __tmp.len();
9588 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
9589 } else {
9590 __tmp.len()
9591 }
9592 }
9593}
9594#[doc = "id: 144"]
9595#[doc = "Current motion information from a designated system."]
9596#[derive(Debug, Clone, PartialEq)]
9597#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9598#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9599pub struct FOLLOW_TARGET_DATA {
9600 #[doc = "Timestamp (time since system boot)."]
9601 pub timestamp: u64,
9602 #[doc = "button states or switches of a tracker device"]
9603 pub custom_state: u64,
9604 #[doc = "Latitude (WGS84)"]
9605 pub lat: i32,
9606 #[doc = "Longitude (WGS84)"]
9607 pub lon: i32,
9608 #[doc = "Altitude (MSL)"]
9609 pub alt: f32,
9610 #[doc = "target velocity (0,0,0) for unknown"]
9611 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
9612 pub vel: [f32; 3],
9613 #[doc = "linear target acceleration (0,0,0) for unknown"]
9614 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
9615 pub acc: [f32; 3],
9616 #[doc = "(0 0 0 0 for unknown)"]
9617 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
9618 pub attitude_q: [f32; 4],
9619 #[doc = "(0 0 0 for unknown)"]
9620 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
9621 pub rates: [f32; 3],
9622 #[doc = "eph epv"]
9623 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
9624 pub position_cov: [f32; 3],
9625 #[doc = "bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3)"]
9626 pub est_capabilities: u8,
9627}
9628impl FOLLOW_TARGET_DATA {
9629 pub const ENCODED_LEN: usize = 93usize;
9630 pub const DEFAULT: Self = Self {
9631 timestamp: 0_u64,
9632 custom_state: 0_u64,
9633 lat: 0_i32,
9634 lon: 0_i32,
9635 alt: 0.0_f32,
9636 vel: [0.0_f32; 3usize],
9637 acc: [0.0_f32; 3usize],
9638 attitude_q: [0.0_f32; 4usize],
9639 rates: [0.0_f32; 3usize],
9640 position_cov: [0.0_f32; 3usize],
9641 est_capabilities: 0_u8,
9642 };
9643 #[cfg(feature = "arbitrary")]
9644 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9645 use arbitrary::{Arbitrary, Unstructured};
9646 let mut buf = [0u8; 1024];
9647 rng.fill_bytes(&mut buf);
9648 let mut unstructured = Unstructured::new(&buf);
9649 Self::arbitrary(&mut unstructured).unwrap_or_default()
9650 }
9651}
9652impl Default for FOLLOW_TARGET_DATA {
9653 fn default() -> Self {
9654 Self::DEFAULT.clone()
9655 }
9656}
9657impl MessageData for FOLLOW_TARGET_DATA {
9658 type Message = MavMessage;
9659 const ID: u32 = 144u32;
9660 const NAME: &'static str = "FOLLOW_TARGET";
9661 const EXTRA_CRC: u8 = 127u8;
9662 const ENCODED_LEN: usize = 93usize;
9663 fn deser(
9664 _version: MavlinkVersion,
9665 __input: &[u8],
9666 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9667 let avail_len = __input.len();
9668 let mut payload_buf = [0; Self::ENCODED_LEN];
9669 let mut buf = if avail_len < Self::ENCODED_LEN {
9670 payload_buf[0..avail_len].copy_from_slice(__input);
9671 Bytes::new(&payload_buf)
9672 } else {
9673 Bytes::new(__input)
9674 };
9675 let mut __struct = Self::default();
9676 __struct.timestamp = buf.get_u64_le();
9677 __struct.custom_state = buf.get_u64_le();
9678 __struct.lat = buf.get_i32_le();
9679 __struct.lon = buf.get_i32_le();
9680 __struct.alt = buf.get_f32_le();
9681 for v in &mut __struct.vel {
9682 let val = buf.get_f32_le();
9683 *v = val;
9684 }
9685 for v in &mut __struct.acc {
9686 let val = buf.get_f32_le();
9687 *v = val;
9688 }
9689 for v in &mut __struct.attitude_q {
9690 let val = buf.get_f32_le();
9691 *v = val;
9692 }
9693 for v in &mut __struct.rates {
9694 let val = buf.get_f32_le();
9695 *v = val;
9696 }
9697 for v in &mut __struct.position_cov {
9698 let val = buf.get_f32_le();
9699 *v = val;
9700 }
9701 __struct.est_capabilities = buf.get_u8();
9702 Ok(__struct)
9703 }
9704 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
9705 let mut __tmp = BytesMut::new(bytes);
9706 #[allow(clippy::absurd_extreme_comparisons)]
9707 #[allow(unused_comparisons)]
9708 if __tmp.remaining() < Self::ENCODED_LEN {
9709 panic!(
9710 "buffer is too small (need {} bytes, but got {})",
9711 Self::ENCODED_LEN,
9712 __tmp.remaining(),
9713 )
9714 }
9715 __tmp.put_u64_le(self.timestamp);
9716 __tmp.put_u64_le(self.custom_state);
9717 __tmp.put_i32_le(self.lat);
9718 __tmp.put_i32_le(self.lon);
9719 __tmp.put_f32_le(self.alt);
9720 for val in &self.vel {
9721 __tmp.put_f32_le(*val);
9722 }
9723 for val in &self.acc {
9724 __tmp.put_f32_le(*val);
9725 }
9726 for val in &self.attitude_q {
9727 __tmp.put_f32_le(*val);
9728 }
9729 for val in &self.rates {
9730 __tmp.put_f32_le(*val);
9731 }
9732 for val in &self.position_cov {
9733 __tmp.put_f32_le(*val);
9734 }
9735 __tmp.put_u8(self.est_capabilities);
9736 if matches!(version, MavlinkVersion::V2) {
9737 let len = __tmp.len();
9738 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
9739 } else {
9740 __tmp.len()
9741 }
9742 }
9743}
9744#[doc = "id: 35"]
9745#[doc = "The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. A value of UINT16_MAX implies the channel is unused. Individual receivers/transmitters might violate this specification."]
9746#[derive(Debug, Clone, PartialEq)]
9747#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9748#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9749pub struct RC_CHANNELS_RAW_DATA {
9750 #[doc = "Timestamp (time since system boot)."]
9751 pub time_boot_ms: u32,
9752 #[doc = "RC channel 1 value."]
9753 pub chan1_raw: u16,
9754 #[doc = "RC channel 2 value."]
9755 pub chan2_raw: u16,
9756 #[doc = "RC channel 3 value."]
9757 pub chan3_raw: u16,
9758 #[doc = "RC channel 4 value."]
9759 pub chan4_raw: u16,
9760 #[doc = "RC channel 5 value."]
9761 pub chan5_raw: u16,
9762 #[doc = "RC channel 6 value."]
9763 pub chan6_raw: u16,
9764 #[doc = "RC channel 7 value."]
9765 pub chan7_raw: u16,
9766 #[doc = "RC channel 8 value."]
9767 pub chan8_raw: u16,
9768 #[doc = "Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX."]
9769 pub port: u8,
9770 #[doc = "Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown."]
9771 pub rssi: u8,
9772}
9773impl RC_CHANNELS_RAW_DATA {
9774 pub const ENCODED_LEN: usize = 22usize;
9775 pub const DEFAULT: Self = Self {
9776 time_boot_ms: 0_u32,
9777 chan1_raw: 0_u16,
9778 chan2_raw: 0_u16,
9779 chan3_raw: 0_u16,
9780 chan4_raw: 0_u16,
9781 chan5_raw: 0_u16,
9782 chan6_raw: 0_u16,
9783 chan7_raw: 0_u16,
9784 chan8_raw: 0_u16,
9785 port: 0_u8,
9786 rssi: 0_u8,
9787 };
9788 #[cfg(feature = "arbitrary")]
9789 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9790 use arbitrary::{Arbitrary, Unstructured};
9791 let mut buf = [0u8; 1024];
9792 rng.fill_bytes(&mut buf);
9793 let mut unstructured = Unstructured::new(&buf);
9794 Self::arbitrary(&mut unstructured).unwrap_or_default()
9795 }
9796}
9797impl Default for RC_CHANNELS_RAW_DATA {
9798 fn default() -> Self {
9799 Self::DEFAULT.clone()
9800 }
9801}
9802impl MessageData for RC_CHANNELS_RAW_DATA {
9803 type Message = MavMessage;
9804 const ID: u32 = 35u32;
9805 const NAME: &'static str = "RC_CHANNELS_RAW";
9806 const EXTRA_CRC: u8 = 244u8;
9807 const ENCODED_LEN: usize = 22usize;
9808 fn deser(
9809 _version: MavlinkVersion,
9810 __input: &[u8],
9811 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9812 let avail_len = __input.len();
9813 let mut payload_buf = [0; Self::ENCODED_LEN];
9814 let mut buf = if avail_len < Self::ENCODED_LEN {
9815 payload_buf[0..avail_len].copy_from_slice(__input);
9816 Bytes::new(&payload_buf)
9817 } else {
9818 Bytes::new(__input)
9819 };
9820 let mut __struct = Self::default();
9821 __struct.time_boot_ms = buf.get_u32_le();
9822 __struct.chan1_raw = buf.get_u16_le();
9823 __struct.chan2_raw = buf.get_u16_le();
9824 __struct.chan3_raw = buf.get_u16_le();
9825 __struct.chan4_raw = buf.get_u16_le();
9826 __struct.chan5_raw = buf.get_u16_le();
9827 __struct.chan6_raw = buf.get_u16_le();
9828 __struct.chan7_raw = buf.get_u16_le();
9829 __struct.chan8_raw = buf.get_u16_le();
9830 __struct.port = buf.get_u8();
9831 __struct.rssi = buf.get_u8();
9832 Ok(__struct)
9833 }
9834 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
9835 let mut __tmp = BytesMut::new(bytes);
9836 #[allow(clippy::absurd_extreme_comparisons)]
9837 #[allow(unused_comparisons)]
9838 if __tmp.remaining() < Self::ENCODED_LEN {
9839 panic!(
9840 "buffer is too small (need {} bytes, but got {})",
9841 Self::ENCODED_LEN,
9842 __tmp.remaining(),
9843 )
9844 }
9845 __tmp.put_u32_le(self.time_boot_ms);
9846 __tmp.put_u16_le(self.chan1_raw);
9847 __tmp.put_u16_le(self.chan2_raw);
9848 __tmp.put_u16_le(self.chan3_raw);
9849 __tmp.put_u16_le(self.chan4_raw);
9850 __tmp.put_u16_le(self.chan5_raw);
9851 __tmp.put_u16_le(self.chan6_raw);
9852 __tmp.put_u16_le(self.chan7_raw);
9853 __tmp.put_u16_le(self.chan8_raw);
9854 __tmp.put_u8(self.port);
9855 __tmp.put_u8(self.rssi);
9856 if matches!(version, MavlinkVersion::V2) {
9857 let len = __tmp.len();
9858 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
9859 } else {
9860 __tmp.len()
9861 }
9862 }
9863}
9864#[doc = "id: 139"]
9865#[doc = "Set the vehicle attitude and body angular rates."]
9866#[derive(Debug, Clone, PartialEq)]
9867#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9868#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9869pub struct SET_ACTUATOR_CONTROL_TARGET_DATA {
9870 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
9871 pub time_usec: u64,
9872 #[doc = "Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs."]
9873 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
9874 pub controls: [f32; 8],
9875 #[doc = "Actuator group. The \"_mlx\" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances."]
9876 pub group_mlx: u8,
9877 #[doc = "System ID"]
9878 pub target_system: u8,
9879 #[doc = "Component ID"]
9880 pub target_component: u8,
9881}
9882impl SET_ACTUATOR_CONTROL_TARGET_DATA {
9883 pub const ENCODED_LEN: usize = 43usize;
9884 pub const DEFAULT: Self = Self {
9885 time_usec: 0_u64,
9886 controls: [0.0_f32; 8usize],
9887 group_mlx: 0_u8,
9888 target_system: 0_u8,
9889 target_component: 0_u8,
9890 };
9891 #[cfg(feature = "arbitrary")]
9892 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9893 use arbitrary::{Arbitrary, Unstructured};
9894 let mut buf = [0u8; 1024];
9895 rng.fill_bytes(&mut buf);
9896 let mut unstructured = Unstructured::new(&buf);
9897 Self::arbitrary(&mut unstructured).unwrap_or_default()
9898 }
9899}
9900impl Default for SET_ACTUATOR_CONTROL_TARGET_DATA {
9901 fn default() -> Self {
9902 Self::DEFAULT.clone()
9903 }
9904}
9905impl MessageData for SET_ACTUATOR_CONTROL_TARGET_DATA {
9906 type Message = MavMessage;
9907 const ID: u32 = 139u32;
9908 const NAME: &'static str = "SET_ACTUATOR_CONTROL_TARGET";
9909 const EXTRA_CRC: u8 = 168u8;
9910 const ENCODED_LEN: usize = 43usize;
9911 fn deser(
9912 _version: MavlinkVersion,
9913 __input: &[u8],
9914 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9915 let avail_len = __input.len();
9916 let mut payload_buf = [0; Self::ENCODED_LEN];
9917 let mut buf = if avail_len < Self::ENCODED_LEN {
9918 payload_buf[0..avail_len].copy_from_slice(__input);
9919 Bytes::new(&payload_buf)
9920 } else {
9921 Bytes::new(__input)
9922 };
9923 let mut __struct = Self::default();
9924 __struct.time_usec = buf.get_u64_le();
9925 for v in &mut __struct.controls {
9926 let val = buf.get_f32_le();
9927 *v = val;
9928 }
9929 __struct.group_mlx = buf.get_u8();
9930 __struct.target_system = buf.get_u8();
9931 __struct.target_component = buf.get_u8();
9932 Ok(__struct)
9933 }
9934 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
9935 let mut __tmp = BytesMut::new(bytes);
9936 #[allow(clippy::absurd_extreme_comparisons)]
9937 #[allow(unused_comparisons)]
9938 if __tmp.remaining() < Self::ENCODED_LEN {
9939 panic!(
9940 "buffer is too small (need {} bytes, but got {})",
9941 Self::ENCODED_LEN,
9942 __tmp.remaining(),
9943 )
9944 }
9945 __tmp.put_u64_le(self.time_usec);
9946 for val in &self.controls {
9947 __tmp.put_f32_le(*val);
9948 }
9949 __tmp.put_u8(self.group_mlx);
9950 __tmp.put_u8(self.target_system);
9951 __tmp.put_u8(self.target_component);
9952 if matches!(version, MavlinkVersion::V2) {
9953 let len = __tmp.len();
9954 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
9955 } else {
9956 __tmp.len()
9957 }
9958 }
9959}
9960#[doc = "id: 246"]
9961#[doc = "The location and information of an ADSB vehicle."]
9962#[derive(Debug, Clone, PartialEq)]
9963#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9964#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9965pub struct ADSB_VEHICLE_DATA {
9966 #[doc = "ICAO address"]
9967 pub ICAO_address: u32,
9968 #[doc = "Latitude"]
9969 pub lat: i32,
9970 #[doc = "Longitude"]
9971 pub lon: i32,
9972 #[doc = "Altitude(ASL)"]
9973 pub altitude: i32,
9974 #[doc = "Course over ground"]
9975 pub heading: u16,
9976 #[doc = "The horizontal velocity"]
9977 pub hor_velocity: u16,
9978 #[doc = "The vertical velocity. Positive is up"]
9979 pub ver_velocity: i16,
9980 #[doc = "Bitmap to indicate various statuses including valid data fields"]
9981 pub flags: AdsbFlags,
9982 #[doc = "Squawk code. Note that the code is in decimal: e.g. 7700 (general emergency) is encoded as binary 0b0001_1110_0001_0100, not(!) as 0b0000_111_111_000_000"]
9983 pub squawk: u16,
9984 #[doc = "ADSB altitude type."]
9985 pub altitude_type: AdsbAltitudeType,
9986 #[doc = "The callsign, 8+null"]
9987 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
9988 pub callsign: [u8; 9],
9989 #[doc = "ADSB emitter type."]
9990 pub emitter_type: AdsbEmitterType,
9991 #[doc = "Time since last communication in seconds"]
9992 pub tslc: u8,
9993}
9994impl ADSB_VEHICLE_DATA {
9995 pub const ENCODED_LEN: usize = 38usize;
9996 pub const DEFAULT: Self = Self {
9997 ICAO_address: 0_u32,
9998 lat: 0_i32,
9999 lon: 0_i32,
10000 altitude: 0_i32,
10001 heading: 0_u16,
10002 hor_velocity: 0_u16,
10003 ver_velocity: 0_i16,
10004 flags: AdsbFlags::DEFAULT,
10005 squawk: 0_u16,
10006 altitude_type: AdsbAltitudeType::DEFAULT,
10007 callsign: [0_u8; 9usize],
10008 emitter_type: AdsbEmitterType::DEFAULT,
10009 tslc: 0_u8,
10010 };
10011 #[cfg(feature = "arbitrary")]
10012 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10013 use arbitrary::{Arbitrary, Unstructured};
10014 let mut buf = [0u8; 1024];
10015 rng.fill_bytes(&mut buf);
10016 let mut unstructured = Unstructured::new(&buf);
10017 Self::arbitrary(&mut unstructured).unwrap_or_default()
10018 }
10019}
10020impl Default for ADSB_VEHICLE_DATA {
10021 fn default() -> Self {
10022 Self::DEFAULT.clone()
10023 }
10024}
10025impl MessageData for ADSB_VEHICLE_DATA {
10026 type Message = MavMessage;
10027 const ID: u32 = 246u32;
10028 const NAME: &'static str = "ADSB_VEHICLE";
10029 const EXTRA_CRC: u8 = 184u8;
10030 const ENCODED_LEN: usize = 38usize;
10031 fn deser(
10032 _version: MavlinkVersion,
10033 __input: &[u8],
10034 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10035 let avail_len = __input.len();
10036 let mut payload_buf = [0; Self::ENCODED_LEN];
10037 let mut buf = if avail_len < Self::ENCODED_LEN {
10038 payload_buf[0..avail_len].copy_from_slice(__input);
10039 Bytes::new(&payload_buf)
10040 } else {
10041 Bytes::new(__input)
10042 };
10043 let mut __struct = Self::default();
10044 __struct.ICAO_address = buf.get_u32_le();
10045 __struct.lat = buf.get_i32_le();
10046 __struct.lon = buf.get_i32_le();
10047 __struct.altitude = buf.get_i32_le();
10048 __struct.heading = buf.get_u16_le();
10049 __struct.hor_velocity = buf.get_u16_le();
10050 __struct.ver_velocity = buf.get_i16_le();
10051 let tmp = buf.get_u16_le();
10052 __struct.flags = AdsbFlags::from_bits(tmp & AdsbFlags::all().bits()).ok_or(
10053 ::mavlink_core::error::ParserError::InvalidFlag {
10054 flag_type: "AdsbFlags",
10055 value: tmp as u32,
10056 },
10057 )?;
10058 __struct.squawk = buf.get_u16_le();
10059 let tmp = buf.get_u8();
10060 __struct.altitude_type =
10061 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
10062 enum_type: "AdsbAltitudeType",
10063 value: tmp as u32,
10064 })?;
10065 for v in &mut __struct.callsign {
10066 let val = buf.get_u8();
10067 *v = val;
10068 }
10069 let tmp = buf.get_u8();
10070 __struct.emitter_type =
10071 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
10072 enum_type: "AdsbEmitterType",
10073 value: tmp as u32,
10074 })?;
10075 __struct.tslc = buf.get_u8();
10076 Ok(__struct)
10077 }
10078 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10079 let mut __tmp = BytesMut::new(bytes);
10080 #[allow(clippy::absurd_extreme_comparisons)]
10081 #[allow(unused_comparisons)]
10082 if __tmp.remaining() < Self::ENCODED_LEN {
10083 panic!(
10084 "buffer is too small (need {} bytes, but got {})",
10085 Self::ENCODED_LEN,
10086 __tmp.remaining(),
10087 )
10088 }
10089 __tmp.put_u32_le(self.ICAO_address);
10090 __tmp.put_i32_le(self.lat);
10091 __tmp.put_i32_le(self.lon);
10092 __tmp.put_i32_le(self.altitude);
10093 __tmp.put_u16_le(self.heading);
10094 __tmp.put_u16_le(self.hor_velocity);
10095 __tmp.put_i16_le(self.ver_velocity);
10096 __tmp.put_u16_le(self.flags.bits());
10097 __tmp.put_u16_le(self.squawk);
10098 __tmp.put_u8(self.altitude_type as u8);
10099 for val in &self.callsign {
10100 __tmp.put_u8(*val);
10101 }
10102 __tmp.put_u8(self.emitter_type as u8);
10103 __tmp.put_u8(self.tslc);
10104 if matches!(version, MavlinkVersion::V2) {
10105 let len = __tmp.len();
10106 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10107 } else {
10108 __tmp.len()
10109 }
10110 }
10111}
10112#[doc = "id: 311"]
10113#[doc = "General information describing a particular UAVCAN node. Please refer to the definition of the UAVCAN service \"uavcan.protocol.GetNodeInfo\" for the background information. This message should be emitted by the system whenever a new node appears online, or an existing node reboots. Additionally, it can be emitted upon request from the other end of the MAVLink channel (see MAV_CMD_UAVCAN_GET_NODE_INFO). It is also not prohibited to emit this message unconditionally at a low frequency. The UAVCAN specification is available at <http://uavcan.org>."]
10114#[derive(Debug, Clone, PartialEq)]
10115#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10116#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10117pub struct UAVCAN_NODE_INFO_DATA {
10118 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
10119 pub time_usec: u64,
10120 #[doc = "Time since the start-up of the node."]
10121 pub uptime_sec: u32,
10122 #[doc = "Version control system (VCS) revision identifier (e.g. git short commit hash). 0 if unknown."]
10123 pub sw_vcs_commit: u32,
10124 #[doc = "Node name string. For example, \"sapog.px4.io\"."]
10125 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
10126 pub name: [u8; 80],
10127 #[doc = "Hardware major version number."]
10128 pub hw_version_major: u8,
10129 #[doc = "Hardware minor version number."]
10130 pub hw_version_minor: u8,
10131 #[doc = "Hardware unique 128-bit ID."]
10132 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
10133 pub hw_unique_id: [u8; 16],
10134 #[doc = "Software major version number."]
10135 pub sw_version_major: u8,
10136 #[doc = "Software minor version number."]
10137 pub sw_version_minor: u8,
10138}
10139impl UAVCAN_NODE_INFO_DATA {
10140 pub const ENCODED_LEN: usize = 116usize;
10141 pub const DEFAULT: Self = Self {
10142 time_usec: 0_u64,
10143 uptime_sec: 0_u32,
10144 sw_vcs_commit: 0_u32,
10145 name: [0_u8; 80usize],
10146 hw_version_major: 0_u8,
10147 hw_version_minor: 0_u8,
10148 hw_unique_id: [0_u8; 16usize],
10149 sw_version_major: 0_u8,
10150 sw_version_minor: 0_u8,
10151 };
10152 #[cfg(feature = "arbitrary")]
10153 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10154 use arbitrary::{Arbitrary, Unstructured};
10155 let mut buf = [0u8; 1024];
10156 rng.fill_bytes(&mut buf);
10157 let mut unstructured = Unstructured::new(&buf);
10158 Self::arbitrary(&mut unstructured).unwrap_or_default()
10159 }
10160}
10161impl Default for UAVCAN_NODE_INFO_DATA {
10162 fn default() -> Self {
10163 Self::DEFAULT.clone()
10164 }
10165}
10166impl MessageData for UAVCAN_NODE_INFO_DATA {
10167 type Message = MavMessage;
10168 const ID: u32 = 311u32;
10169 const NAME: &'static str = "UAVCAN_NODE_INFO";
10170 const EXTRA_CRC: u8 = 95u8;
10171 const ENCODED_LEN: usize = 116usize;
10172 fn deser(
10173 _version: MavlinkVersion,
10174 __input: &[u8],
10175 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10176 let avail_len = __input.len();
10177 let mut payload_buf = [0; Self::ENCODED_LEN];
10178 let mut buf = if avail_len < Self::ENCODED_LEN {
10179 payload_buf[0..avail_len].copy_from_slice(__input);
10180 Bytes::new(&payload_buf)
10181 } else {
10182 Bytes::new(__input)
10183 };
10184 let mut __struct = Self::default();
10185 __struct.time_usec = buf.get_u64_le();
10186 __struct.uptime_sec = buf.get_u32_le();
10187 __struct.sw_vcs_commit = buf.get_u32_le();
10188 for v in &mut __struct.name {
10189 let val = buf.get_u8();
10190 *v = val;
10191 }
10192 __struct.hw_version_major = buf.get_u8();
10193 __struct.hw_version_minor = buf.get_u8();
10194 for v in &mut __struct.hw_unique_id {
10195 let val = buf.get_u8();
10196 *v = val;
10197 }
10198 __struct.sw_version_major = buf.get_u8();
10199 __struct.sw_version_minor = buf.get_u8();
10200 Ok(__struct)
10201 }
10202 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10203 let mut __tmp = BytesMut::new(bytes);
10204 #[allow(clippy::absurd_extreme_comparisons)]
10205 #[allow(unused_comparisons)]
10206 if __tmp.remaining() < Self::ENCODED_LEN {
10207 panic!(
10208 "buffer is too small (need {} bytes, but got {})",
10209 Self::ENCODED_LEN,
10210 __tmp.remaining(),
10211 )
10212 }
10213 __tmp.put_u64_le(self.time_usec);
10214 __tmp.put_u32_le(self.uptime_sec);
10215 __tmp.put_u32_le(self.sw_vcs_commit);
10216 for val in &self.name {
10217 __tmp.put_u8(*val);
10218 }
10219 __tmp.put_u8(self.hw_version_major);
10220 __tmp.put_u8(self.hw_version_minor);
10221 for val in &self.hw_unique_id {
10222 __tmp.put_u8(*val);
10223 }
10224 __tmp.put_u8(self.sw_version_major);
10225 __tmp.put_u8(self.sw_version_minor);
10226 if matches!(version, MavlinkVersion::V2) {
10227 let len = __tmp.len();
10228 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10229 } else {
10230 __tmp.len()
10231 }
10232 }
10233}
10234#[doc = "id: 310"]
10235#[doc = "General status information of an UAVCAN node. Please refer to the definition of the UAVCAN message \"uavcan.protocol.NodeStatus\" for the background information. The UAVCAN specification is available at <http://uavcan.org>."]
10236#[derive(Debug, Clone, PartialEq)]
10237#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10238#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10239pub struct UAVCAN_NODE_STATUS_DATA {
10240 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
10241 pub time_usec: u64,
10242 #[doc = "Time since the start-up of the node."]
10243 pub uptime_sec: u32,
10244 #[doc = "Vendor-specific status information."]
10245 pub vendor_specific_status_code: u16,
10246 #[doc = "Generalized node health status."]
10247 pub health: UavcanNodeHealth,
10248 #[doc = "Generalized operating mode."]
10249 pub mode: UavcanNodeMode,
10250 #[doc = "Not used currently."]
10251 pub sub_mode: u8,
10252}
10253impl UAVCAN_NODE_STATUS_DATA {
10254 pub const ENCODED_LEN: usize = 17usize;
10255 pub const DEFAULT: Self = Self {
10256 time_usec: 0_u64,
10257 uptime_sec: 0_u32,
10258 vendor_specific_status_code: 0_u16,
10259 health: UavcanNodeHealth::DEFAULT,
10260 mode: UavcanNodeMode::DEFAULT,
10261 sub_mode: 0_u8,
10262 };
10263 #[cfg(feature = "arbitrary")]
10264 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10265 use arbitrary::{Arbitrary, Unstructured};
10266 let mut buf = [0u8; 1024];
10267 rng.fill_bytes(&mut buf);
10268 let mut unstructured = Unstructured::new(&buf);
10269 Self::arbitrary(&mut unstructured).unwrap_or_default()
10270 }
10271}
10272impl Default for UAVCAN_NODE_STATUS_DATA {
10273 fn default() -> Self {
10274 Self::DEFAULT.clone()
10275 }
10276}
10277impl MessageData for UAVCAN_NODE_STATUS_DATA {
10278 type Message = MavMessage;
10279 const ID: u32 = 310u32;
10280 const NAME: &'static str = "UAVCAN_NODE_STATUS";
10281 const EXTRA_CRC: u8 = 28u8;
10282 const ENCODED_LEN: usize = 17usize;
10283 fn deser(
10284 _version: MavlinkVersion,
10285 __input: &[u8],
10286 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10287 let avail_len = __input.len();
10288 let mut payload_buf = [0; Self::ENCODED_LEN];
10289 let mut buf = if avail_len < Self::ENCODED_LEN {
10290 payload_buf[0..avail_len].copy_from_slice(__input);
10291 Bytes::new(&payload_buf)
10292 } else {
10293 Bytes::new(__input)
10294 };
10295 let mut __struct = Self::default();
10296 __struct.time_usec = buf.get_u64_le();
10297 __struct.uptime_sec = buf.get_u32_le();
10298 __struct.vendor_specific_status_code = buf.get_u16_le();
10299 let tmp = buf.get_u8();
10300 __struct.health =
10301 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
10302 enum_type: "UavcanNodeHealth",
10303 value: tmp as u32,
10304 })?;
10305 let tmp = buf.get_u8();
10306 __struct.mode =
10307 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
10308 enum_type: "UavcanNodeMode",
10309 value: tmp as u32,
10310 })?;
10311 __struct.sub_mode = buf.get_u8();
10312 Ok(__struct)
10313 }
10314 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10315 let mut __tmp = BytesMut::new(bytes);
10316 #[allow(clippy::absurd_extreme_comparisons)]
10317 #[allow(unused_comparisons)]
10318 if __tmp.remaining() < Self::ENCODED_LEN {
10319 panic!(
10320 "buffer is too small (need {} bytes, but got {})",
10321 Self::ENCODED_LEN,
10322 __tmp.remaining(),
10323 )
10324 }
10325 __tmp.put_u64_le(self.time_usec);
10326 __tmp.put_u32_le(self.uptime_sec);
10327 __tmp.put_u16_le(self.vendor_specific_status_code);
10328 __tmp.put_u8(self.health as u8);
10329 __tmp.put_u8(self.mode as u8);
10330 __tmp.put_u8(self.sub_mode);
10331 if matches!(version, MavlinkVersion::V2) {
10332 let len = __tmp.len();
10333 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10334 } else {
10335 __tmp.len()
10336 }
10337 }
10338}
10339#[doc = "id: 101"]
10340#[doc = "Global position/attitude estimate from a vision source."]
10341#[derive(Debug, Clone, PartialEq)]
10342#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10343#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10344pub struct GLOBAL_VISION_POSITION_ESTIMATE_DATA {
10345 #[doc = "Timestamp (UNIX time or since system boot)"]
10346 pub usec: u64,
10347 #[doc = "Global X position"]
10348 pub x: f32,
10349 #[doc = "Global Y position"]
10350 pub y: f32,
10351 #[doc = "Global Z position"]
10352 pub z: f32,
10353 #[doc = "Roll angle"]
10354 pub roll: f32,
10355 #[doc = "Pitch angle"]
10356 pub pitch: f32,
10357 #[doc = "Yaw angle"]
10358 pub yaw: f32,
10359 #[doc = "Row-major representation of pose 6x6 cross-covariance matrix upper right triangle (states: x_global, y_global, z_global, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array."]
10360 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
10361 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
10362 pub covariance: [f32; 21],
10363 #[doc = "Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps."]
10364 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
10365 pub reset_counter: u8,
10366}
10367impl GLOBAL_VISION_POSITION_ESTIMATE_DATA {
10368 pub const ENCODED_LEN: usize = 117usize;
10369 pub const DEFAULT: Self = Self {
10370 usec: 0_u64,
10371 x: 0.0_f32,
10372 y: 0.0_f32,
10373 z: 0.0_f32,
10374 roll: 0.0_f32,
10375 pitch: 0.0_f32,
10376 yaw: 0.0_f32,
10377 covariance: [0.0_f32; 21usize],
10378 reset_counter: 0_u8,
10379 };
10380 #[cfg(feature = "arbitrary")]
10381 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10382 use arbitrary::{Arbitrary, Unstructured};
10383 let mut buf = [0u8; 1024];
10384 rng.fill_bytes(&mut buf);
10385 let mut unstructured = Unstructured::new(&buf);
10386 Self::arbitrary(&mut unstructured).unwrap_or_default()
10387 }
10388}
10389impl Default for GLOBAL_VISION_POSITION_ESTIMATE_DATA {
10390 fn default() -> Self {
10391 Self::DEFAULT.clone()
10392 }
10393}
10394impl MessageData for GLOBAL_VISION_POSITION_ESTIMATE_DATA {
10395 type Message = MavMessage;
10396 const ID: u32 = 101u32;
10397 const NAME: &'static str = "GLOBAL_VISION_POSITION_ESTIMATE";
10398 const EXTRA_CRC: u8 = 102u8;
10399 const ENCODED_LEN: usize = 117usize;
10400 fn deser(
10401 _version: MavlinkVersion,
10402 __input: &[u8],
10403 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10404 let avail_len = __input.len();
10405 let mut payload_buf = [0; Self::ENCODED_LEN];
10406 let mut buf = if avail_len < Self::ENCODED_LEN {
10407 payload_buf[0..avail_len].copy_from_slice(__input);
10408 Bytes::new(&payload_buf)
10409 } else {
10410 Bytes::new(__input)
10411 };
10412 let mut __struct = Self::default();
10413 __struct.usec = buf.get_u64_le();
10414 __struct.x = buf.get_f32_le();
10415 __struct.y = buf.get_f32_le();
10416 __struct.z = buf.get_f32_le();
10417 __struct.roll = buf.get_f32_le();
10418 __struct.pitch = buf.get_f32_le();
10419 __struct.yaw = buf.get_f32_le();
10420 for v in &mut __struct.covariance {
10421 let val = buf.get_f32_le();
10422 *v = val;
10423 }
10424 __struct.reset_counter = buf.get_u8();
10425 Ok(__struct)
10426 }
10427 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10428 let mut __tmp = BytesMut::new(bytes);
10429 #[allow(clippy::absurd_extreme_comparisons)]
10430 #[allow(unused_comparisons)]
10431 if __tmp.remaining() < Self::ENCODED_LEN {
10432 panic!(
10433 "buffer is too small (need {} bytes, but got {})",
10434 Self::ENCODED_LEN,
10435 __tmp.remaining(),
10436 )
10437 }
10438 __tmp.put_u64_le(self.usec);
10439 __tmp.put_f32_le(self.x);
10440 __tmp.put_f32_le(self.y);
10441 __tmp.put_f32_le(self.z);
10442 __tmp.put_f32_le(self.roll);
10443 __tmp.put_f32_le(self.pitch);
10444 __tmp.put_f32_le(self.yaw);
10445 for val in &self.covariance {
10446 __tmp.put_f32_le(*val);
10447 }
10448 __tmp.put_u8(self.reset_counter);
10449 if matches!(version, MavlinkVersion::V2) {
10450 let len = __tmp.len();
10451 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10452 } else {
10453 __tmp.len()
10454 }
10455 }
10456}
10457#[doc = "id: 248"]
10458#[doc = "Message implementing parts of the V2 payload specs in V1 frames for transitional support."]
10459#[derive(Debug, Clone, PartialEq)]
10460#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10461#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10462pub struct V2_EXTENSION_DATA {
10463 #[doc = "A code that identifies the software component that understands this message (analogous to USB device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to <https://github.com/mavlink/mavlink/definition_files/extension_message_ids.xml>. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase."]
10464 pub message_type: u16,
10465 #[doc = "Network ID (0 for broadcast)"]
10466 pub target_network: u8,
10467 #[doc = "System ID (0 for broadcast)"]
10468 pub target_system: u8,
10469 #[doc = "Component ID (0 for broadcast)"]
10470 pub target_component: u8,
10471 #[doc = "Variable length payload. The length must be encoded in the payload as part of the message_type protocol, e.g. by including the length as payload data, or by terminating the payload data with a non-zero marker. This is required in order to reconstruct zero-terminated payloads that are (or otherwise would be) trimmed by MAVLink 2 empty-byte truncation. The entire content of the payload block is opaque unless you understand the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the MAVLink specification."]
10472 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
10473 pub payload: [u8; 249],
10474}
10475impl V2_EXTENSION_DATA {
10476 pub const ENCODED_LEN: usize = 254usize;
10477 pub const DEFAULT: Self = Self {
10478 message_type: 0_u16,
10479 target_network: 0_u8,
10480 target_system: 0_u8,
10481 target_component: 0_u8,
10482 payload: [0_u8; 249usize],
10483 };
10484 #[cfg(feature = "arbitrary")]
10485 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10486 use arbitrary::{Arbitrary, Unstructured};
10487 let mut buf = [0u8; 1024];
10488 rng.fill_bytes(&mut buf);
10489 let mut unstructured = Unstructured::new(&buf);
10490 Self::arbitrary(&mut unstructured).unwrap_or_default()
10491 }
10492}
10493impl Default for V2_EXTENSION_DATA {
10494 fn default() -> Self {
10495 Self::DEFAULT.clone()
10496 }
10497}
10498impl MessageData for V2_EXTENSION_DATA {
10499 type Message = MavMessage;
10500 const ID: u32 = 248u32;
10501 const NAME: &'static str = "V2_EXTENSION";
10502 const EXTRA_CRC: u8 = 8u8;
10503 const ENCODED_LEN: usize = 254usize;
10504 fn deser(
10505 _version: MavlinkVersion,
10506 __input: &[u8],
10507 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10508 let avail_len = __input.len();
10509 let mut payload_buf = [0; Self::ENCODED_LEN];
10510 let mut buf = if avail_len < Self::ENCODED_LEN {
10511 payload_buf[0..avail_len].copy_from_slice(__input);
10512 Bytes::new(&payload_buf)
10513 } else {
10514 Bytes::new(__input)
10515 };
10516 let mut __struct = Self::default();
10517 __struct.message_type = buf.get_u16_le();
10518 __struct.target_network = buf.get_u8();
10519 __struct.target_system = buf.get_u8();
10520 __struct.target_component = buf.get_u8();
10521 for v in &mut __struct.payload {
10522 let val = buf.get_u8();
10523 *v = val;
10524 }
10525 Ok(__struct)
10526 }
10527 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10528 let mut __tmp = BytesMut::new(bytes);
10529 #[allow(clippy::absurd_extreme_comparisons)]
10530 #[allow(unused_comparisons)]
10531 if __tmp.remaining() < Self::ENCODED_LEN {
10532 panic!(
10533 "buffer is too small (need {} bytes, but got {})",
10534 Self::ENCODED_LEN,
10535 __tmp.remaining(),
10536 )
10537 }
10538 __tmp.put_u16_le(self.message_type);
10539 __tmp.put_u8(self.target_network);
10540 __tmp.put_u8(self.target_system);
10541 __tmp.put_u8(self.target_component);
10542 for val in &self.payload {
10543 __tmp.put_u8(*val);
10544 }
10545 if matches!(version, MavlinkVersion::V2) {
10546 let len = __tmp.len();
10547 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10548 } else {
10549 __tmp.len()
10550 }
10551 }
10552}
10553#[doc = "id: 127"]
10554#[doc = "RTK GPS data. Gives information on the relative baseline calculation the GPS is reporting."]
10555#[derive(Debug, Clone, PartialEq)]
10556#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10557#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10558pub struct GPS_RTK_DATA {
10559 #[doc = "Time since boot of last baseline message received."]
10560 pub time_last_baseline_ms: u32,
10561 #[doc = "GPS Time of Week of last baseline"]
10562 pub tow: u32,
10563 #[doc = "Current baseline in ECEF x or NED north component."]
10564 pub baseline_a_mm: i32,
10565 #[doc = "Current baseline in ECEF y or NED east component."]
10566 pub baseline_b_mm: i32,
10567 #[doc = "Current baseline in ECEF z or NED down component."]
10568 pub baseline_c_mm: i32,
10569 #[doc = "Current estimate of baseline accuracy."]
10570 pub accuracy: u32,
10571 #[doc = "Current number of integer ambiguity hypotheses."]
10572 pub iar_num_hypotheses: i32,
10573 #[doc = "GPS Week Number of last baseline"]
10574 pub wn: u16,
10575 #[doc = "Identification of connected RTK receiver."]
10576 pub rtk_receiver_id: u8,
10577 #[doc = "GPS-specific health report for RTK data."]
10578 pub rtk_health: u8,
10579 #[doc = "Rate of baseline messages being received by GPS"]
10580 pub rtk_rate: u8,
10581 #[doc = "Current number of sats used for RTK calculation."]
10582 pub nsats: u8,
10583 #[doc = "Coordinate system of baseline"]
10584 pub baseline_coords_type: RtkBaselineCoordinateSystem,
10585}
10586impl GPS_RTK_DATA {
10587 pub const ENCODED_LEN: usize = 35usize;
10588 pub const DEFAULT: Self = Self {
10589 time_last_baseline_ms: 0_u32,
10590 tow: 0_u32,
10591 baseline_a_mm: 0_i32,
10592 baseline_b_mm: 0_i32,
10593 baseline_c_mm: 0_i32,
10594 accuracy: 0_u32,
10595 iar_num_hypotheses: 0_i32,
10596 wn: 0_u16,
10597 rtk_receiver_id: 0_u8,
10598 rtk_health: 0_u8,
10599 rtk_rate: 0_u8,
10600 nsats: 0_u8,
10601 baseline_coords_type: RtkBaselineCoordinateSystem::DEFAULT,
10602 };
10603 #[cfg(feature = "arbitrary")]
10604 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10605 use arbitrary::{Arbitrary, Unstructured};
10606 let mut buf = [0u8; 1024];
10607 rng.fill_bytes(&mut buf);
10608 let mut unstructured = Unstructured::new(&buf);
10609 Self::arbitrary(&mut unstructured).unwrap_or_default()
10610 }
10611}
10612impl Default for GPS_RTK_DATA {
10613 fn default() -> Self {
10614 Self::DEFAULT.clone()
10615 }
10616}
10617impl MessageData for GPS_RTK_DATA {
10618 type Message = MavMessage;
10619 const ID: u32 = 127u32;
10620 const NAME: &'static str = "GPS_RTK";
10621 const EXTRA_CRC: u8 = 25u8;
10622 const ENCODED_LEN: usize = 35usize;
10623 fn deser(
10624 _version: MavlinkVersion,
10625 __input: &[u8],
10626 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10627 let avail_len = __input.len();
10628 let mut payload_buf = [0; Self::ENCODED_LEN];
10629 let mut buf = if avail_len < Self::ENCODED_LEN {
10630 payload_buf[0..avail_len].copy_from_slice(__input);
10631 Bytes::new(&payload_buf)
10632 } else {
10633 Bytes::new(__input)
10634 };
10635 let mut __struct = Self::default();
10636 __struct.time_last_baseline_ms = buf.get_u32_le();
10637 __struct.tow = buf.get_u32_le();
10638 __struct.baseline_a_mm = buf.get_i32_le();
10639 __struct.baseline_b_mm = buf.get_i32_le();
10640 __struct.baseline_c_mm = buf.get_i32_le();
10641 __struct.accuracy = buf.get_u32_le();
10642 __struct.iar_num_hypotheses = buf.get_i32_le();
10643 __struct.wn = buf.get_u16_le();
10644 __struct.rtk_receiver_id = buf.get_u8();
10645 __struct.rtk_health = buf.get_u8();
10646 __struct.rtk_rate = buf.get_u8();
10647 __struct.nsats = buf.get_u8();
10648 let tmp = buf.get_u8();
10649 __struct.baseline_coords_type =
10650 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
10651 enum_type: "RtkBaselineCoordinateSystem",
10652 value: tmp as u32,
10653 })?;
10654 Ok(__struct)
10655 }
10656 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10657 let mut __tmp = BytesMut::new(bytes);
10658 #[allow(clippy::absurd_extreme_comparisons)]
10659 #[allow(unused_comparisons)]
10660 if __tmp.remaining() < Self::ENCODED_LEN {
10661 panic!(
10662 "buffer is too small (need {} bytes, but got {})",
10663 Self::ENCODED_LEN,
10664 __tmp.remaining(),
10665 )
10666 }
10667 __tmp.put_u32_le(self.time_last_baseline_ms);
10668 __tmp.put_u32_le(self.tow);
10669 __tmp.put_i32_le(self.baseline_a_mm);
10670 __tmp.put_i32_le(self.baseline_b_mm);
10671 __tmp.put_i32_le(self.baseline_c_mm);
10672 __tmp.put_u32_le(self.accuracy);
10673 __tmp.put_i32_le(self.iar_num_hypotheses);
10674 __tmp.put_u16_le(self.wn);
10675 __tmp.put_u8(self.rtk_receiver_id);
10676 __tmp.put_u8(self.rtk_health);
10677 __tmp.put_u8(self.rtk_rate);
10678 __tmp.put_u8(self.nsats);
10679 __tmp.put_u8(self.baseline_coords_type as u8);
10680 if matches!(version, MavlinkVersion::V2) {
10681 let len = __tmp.len();
10682 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10683 } else {
10684 __tmp.len()
10685 }
10686 }
10687}
10688#[doc = "id: 299"]
10689#[doc = "Configure WiFi AP SSID, password, and mode. This message is re-emitted as an acknowledgement by the AP. The message may also be explicitly requested using MAV_CMD_REQUEST_MESSAGE."]
10690#[derive(Debug, Clone, PartialEq)]
10691#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10692#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10693pub struct WIFI_CONFIG_AP_DATA {
10694 #[doc = "Name of Wi-Fi network (SSID). Blank to leave it unchanged when setting. Current SSID when sent back as a response."]
10695 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
10696 pub ssid: [u8; 32],
10697 #[doc = "Password. Blank for an open AP. MD5 hash when message is sent back as a response."]
10698 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
10699 pub password: [u8; 64],
10700 #[doc = "WiFi Mode."]
10701 #[cfg_attr(feature = "serde", serde(default))]
10702 pub mode: WifiConfigApMode,
10703 #[doc = "Message acceptance response (sent back to GS)."]
10704 #[cfg_attr(feature = "serde", serde(default))]
10705 pub response: WifiConfigApResponse,
10706}
10707impl WIFI_CONFIG_AP_DATA {
10708 pub const ENCODED_LEN: usize = 98usize;
10709 pub const DEFAULT: Self = Self {
10710 ssid: [0_u8; 32usize],
10711 password: [0_u8; 64usize],
10712 mode: WifiConfigApMode::DEFAULT,
10713 response: WifiConfigApResponse::DEFAULT,
10714 };
10715 #[cfg(feature = "arbitrary")]
10716 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10717 use arbitrary::{Arbitrary, Unstructured};
10718 let mut buf = [0u8; 1024];
10719 rng.fill_bytes(&mut buf);
10720 let mut unstructured = Unstructured::new(&buf);
10721 Self::arbitrary(&mut unstructured).unwrap_or_default()
10722 }
10723}
10724impl Default for WIFI_CONFIG_AP_DATA {
10725 fn default() -> Self {
10726 Self::DEFAULT.clone()
10727 }
10728}
10729impl MessageData for WIFI_CONFIG_AP_DATA {
10730 type Message = MavMessage;
10731 const ID: u32 = 299u32;
10732 const NAME: &'static str = "WIFI_CONFIG_AP";
10733 const EXTRA_CRC: u8 = 19u8;
10734 const ENCODED_LEN: usize = 98usize;
10735 fn deser(
10736 _version: MavlinkVersion,
10737 __input: &[u8],
10738 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10739 let avail_len = __input.len();
10740 let mut payload_buf = [0; Self::ENCODED_LEN];
10741 let mut buf = if avail_len < Self::ENCODED_LEN {
10742 payload_buf[0..avail_len].copy_from_slice(__input);
10743 Bytes::new(&payload_buf)
10744 } else {
10745 Bytes::new(__input)
10746 };
10747 let mut __struct = Self::default();
10748 for v in &mut __struct.ssid {
10749 let val = buf.get_u8();
10750 *v = val;
10751 }
10752 for v in &mut __struct.password {
10753 let val = buf.get_u8();
10754 *v = val;
10755 }
10756 let tmp = buf.get_i8();
10757 __struct.mode =
10758 FromPrimitive::from_i8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
10759 enum_type: "WifiConfigApMode",
10760 value: tmp as u32,
10761 })?;
10762 let tmp = buf.get_i8();
10763 __struct.response =
10764 FromPrimitive::from_i8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
10765 enum_type: "WifiConfigApResponse",
10766 value: tmp as u32,
10767 })?;
10768 Ok(__struct)
10769 }
10770 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10771 let mut __tmp = BytesMut::new(bytes);
10772 #[allow(clippy::absurd_extreme_comparisons)]
10773 #[allow(unused_comparisons)]
10774 if __tmp.remaining() < Self::ENCODED_LEN {
10775 panic!(
10776 "buffer is too small (need {} bytes, but got {})",
10777 Self::ENCODED_LEN,
10778 __tmp.remaining(),
10779 )
10780 }
10781 for val in &self.ssid {
10782 __tmp.put_u8(*val);
10783 }
10784 for val in &self.password {
10785 __tmp.put_u8(*val);
10786 }
10787 __tmp.put_i8(self.mode as i8);
10788 __tmp.put_i8(self.response as i8);
10789 if matches!(version, MavlinkVersion::V2) {
10790 let len = __tmp.len();
10791 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10792 } else {
10793 __tmp.len()
10794 }
10795 }
10796}
10797#[doc = "id: 395"]
10798#[doc = "Component information message, which may be requested using MAV_CMD_REQUEST_MESSAGE."]
10799#[derive(Debug, Clone, PartialEq)]
10800#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10801#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10802pub struct COMPONENT_INFORMATION_DATA {
10803 #[doc = "Timestamp (time since system boot)."]
10804 pub time_boot_ms: u32,
10805 #[doc = "CRC32 of the general metadata file (general_metadata_uri)."]
10806 pub general_metadata_file_crc: u32,
10807 #[doc = "CRC32 of peripherals metadata file (peripherals_metadata_uri)."]
10808 pub peripherals_metadata_file_crc: u32,
10809 #[doc = "MAVLink FTP URI for the general metadata file (COMP_METADATA_TYPE_GENERAL), which may be compressed with xz. The file contains general component metadata, and may contain URI links for additional metadata (see COMP_METADATA_TYPE). The information is static from boot, and may be generated at compile time. The string needs to be zero terminated."]
10810 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
10811 pub general_metadata_uri: [u8; 100],
10812 #[doc = "(Optional) MAVLink FTP URI for the peripherals metadata file (COMP_METADATA_TYPE_PERIPHERALS), which may be compressed with xz. This contains data about \"attached components\" such as UAVCAN nodes. The peripherals are in a separate file because the information must be generated dynamically at runtime. The string needs to be zero terminated."]
10813 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
10814 pub peripherals_metadata_uri: [u8; 100],
10815}
10816impl COMPONENT_INFORMATION_DATA {
10817 pub const ENCODED_LEN: usize = 212usize;
10818 pub const DEFAULT: Self = Self {
10819 time_boot_ms: 0_u32,
10820 general_metadata_file_crc: 0_u32,
10821 peripherals_metadata_file_crc: 0_u32,
10822 general_metadata_uri: [0_u8; 100usize],
10823 peripherals_metadata_uri: [0_u8; 100usize],
10824 };
10825 #[cfg(feature = "arbitrary")]
10826 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10827 use arbitrary::{Arbitrary, Unstructured};
10828 let mut buf = [0u8; 1024];
10829 rng.fill_bytes(&mut buf);
10830 let mut unstructured = Unstructured::new(&buf);
10831 Self::arbitrary(&mut unstructured).unwrap_or_default()
10832 }
10833}
10834impl Default for COMPONENT_INFORMATION_DATA {
10835 fn default() -> Self {
10836 Self::DEFAULT.clone()
10837 }
10838}
10839impl MessageData for COMPONENT_INFORMATION_DATA {
10840 type Message = MavMessage;
10841 const ID: u32 = 395u32;
10842 const NAME: &'static str = "COMPONENT_INFORMATION";
10843 const EXTRA_CRC: u8 = 0u8;
10844 const ENCODED_LEN: usize = 212usize;
10845 fn deser(
10846 _version: MavlinkVersion,
10847 __input: &[u8],
10848 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10849 let avail_len = __input.len();
10850 let mut payload_buf = [0; Self::ENCODED_LEN];
10851 let mut buf = if avail_len < Self::ENCODED_LEN {
10852 payload_buf[0..avail_len].copy_from_slice(__input);
10853 Bytes::new(&payload_buf)
10854 } else {
10855 Bytes::new(__input)
10856 };
10857 let mut __struct = Self::default();
10858 __struct.time_boot_ms = buf.get_u32_le();
10859 __struct.general_metadata_file_crc = buf.get_u32_le();
10860 __struct.peripherals_metadata_file_crc = buf.get_u32_le();
10861 for v in &mut __struct.general_metadata_uri {
10862 let val = buf.get_u8();
10863 *v = val;
10864 }
10865 for v in &mut __struct.peripherals_metadata_uri {
10866 let val = buf.get_u8();
10867 *v = val;
10868 }
10869 Ok(__struct)
10870 }
10871 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10872 let mut __tmp = BytesMut::new(bytes);
10873 #[allow(clippy::absurd_extreme_comparisons)]
10874 #[allow(unused_comparisons)]
10875 if __tmp.remaining() < Self::ENCODED_LEN {
10876 panic!(
10877 "buffer is too small (need {} bytes, but got {})",
10878 Self::ENCODED_LEN,
10879 __tmp.remaining(),
10880 )
10881 }
10882 __tmp.put_u32_le(self.time_boot_ms);
10883 __tmp.put_u32_le(self.general_metadata_file_crc);
10884 __tmp.put_u32_le(self.peripherals_metadata_file_crc);
10885 for val in &self.general_metadata_uri {
10886 __tmp.put_u8(*val);
10887 }
10888 for val in &self.peripherals_metadata_uri {
10889 __tmp.put_u8(*val);
10890 }
10891 if matches!(version, MavlinkVersion::V2) {
10892 let len = __tmp.len();
10893 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10894 } else {
10895 __tmp.len()
10896 }
10897 }
10898}
10899#[doc = "id: 119"]
10900#[doc = "Request a chunk of a log."]
10901#[derive(Debug, Clone, PartialEq)]
10902#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10903#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10904pub struct LOG_REQUEST_DATA_DATA {
10905 #[doc = "Offset into the log"]
10906 pub ofs: u32,
10907 #[doc = "Number of bytes"]
10908 pub count: u32,
10909 #[doc = "Log id (from LOG_ENTRY reply)"]
10910 pub id: u16,
10911 #[doc = "System ID"]
10912 pub target_system: u8,
10913 #[doc = "Component ID"]
10914 pub target_component: u8,
10915}
10916impl LOG_REQUEST_DATA_DATA {
10917 pub const ENCODED_LEN: usize = 12usize;
10918 pub const DEFAULT: Self = Self {
10919 ofs: 0_u32,
10920 count: 0_u32,
10921 id: 0_u16,
10922 target_system: 0_u8,
10923 target_component: 0_u8,
10924 };
10925 #[cfg(feature = "arbitrary")]
10926 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10927 use arbitrary::{Arbitrary, Unstructured};
10928 let mut buf = [0u8; 1024];
10929 rng.fill_bytes(&mut buf);
10930 let mut unstructured = Unstructured::new(&buf);
10931 Self::arbitrary(&mut unstructured).unwrap_or_default()
10932 }
10933}
10934impl Default for LOG_REQUEST_DATA_DATA {
10935 fn default() -> Self {
10936 Self::DEFAULT.clone()
10937 }
10938}
10939impl MessageData for LOG_REQUEST_DATA_DATA {
10940 type Message = MavMessage;
10941 const ID: u32 = 119u32;
10942 const NAME: &'static str = "LOG_REQUEST_DATA";
10943 const EXTRA_CRC: u8 = 116u8;
10944 const ENCODED_LEN: usize = 12usize;
10945 fn deser(
10946 _version: MavlinkVersion,
10947 __input: &[u8],
10948 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10949 let avail_len = __input.len();
10950 let mut payload_buf = [0; Self::ENCODED_LEN];
10951 let mut buf = if avail_len < Self::ENCODED_LEN {
10952 payload_buf[0..avail_len].copy_from_slice(__input);
10953 Bytes::new(&payload_buf)
10954 } else {
10955 Bytes::new(__input)
10956 };
10957 let mut __struct = Self::default();
10958 __struct.ofs = buf.get_u32_le();
10959 __struct.count = buf.get_u32_le();
10960 __struct.id = buf.get_u16_le();
10961 __struct.target_system = buf.get_u8();
10962 __struct.target_component = buf.get_u8();
10963 Ok(__struct)
10964 }
10965 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10966 let mut __tmp = BytesMut::new(bytes);
10967 #[allow(clippy::absurd_extreme_comparisons)]
10968 #[allow(unused_comparisons)]
10969 if __tmp.remaining() < Self::ENCODED_LEN {
10970 panic!(
10971 "buffer is too small (need {} bytes, but got {})",
10972 Self::ENCODED_LEN,
10973 __tmp.remaining(),
10974 )
10975 }
10976 __tmp.put_u32_le(self.ofs);
10977 __tmp.put_u32_le(self.count);
10978 __tmp.put_u16_le(self.id);
10979 __tmp.put_u8(self.target_system);
10980 __tmp.put_u8(self.target_component);
10981 if matches!(version, MavlinkVersion::V2) {
10982 let len = __tmp.len();
10983 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10984 } else {
10985 __tmp.len()
10986 }
10987 }
10988}
10989#[doc = "id: 92"]
10990#[doc = "Sent from simulation to autopilot. The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification."]
10991#[derive(Debug, Clone, PartialEq)]
10992#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10993#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10994pub struct HIL_RC_INPUTS_RAW_DATA {
10995 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
10996 pub time_usec: u64,
10997 #[doc = "RC channel 1 value"]
10998 pub chan1_raw: u16,
10999 #[doc = "RC channel 2 value"]
11000 pub chan2_raw: u16,
11001 #[doc = "RC channel 3 value"]
11002 pub chan3_raw: u16,
11003 #[doc = "RC channel 4 value"]
11004 pub chan4_raw: u16,
11005 #[doc = "RC channel 5 value"]
11006 pub chan5_raw: u16,
11007 #[doc = "RC channel 6 value"]
11008 pub chan6_raw: u16,
11009 #[doc = "RC channel 7 value"]
11010 pub chan7_raw: u16,
11011 #[doc = "RC channel 8 value"]
11012 pub chan8_raw: u16,
11013 #[doc = "RC channel 9 value"]
11014 pub chan9_raw: u16,
11015 #[doc = "RC channel 10 value"]
11016 pub chan10_raw: u16,
11017 #[doc = "RC channel 11 value"]
11018 pub chan11_raw: u16,
11019 #[doc = "RC channel 12 value"]
11020 pub chan12_raw: u16,
11021 #[doc = "Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown."]
11022 pub rssi: u8,
11023}
11024impl HIL_RC_INPUTS_RAW_DATA {
11025 pub const ENCODED_LEN: usize = 33usize;
11026 pub const DEFAULT: Self = Self {
11027 time_usec: 0_u64,
11028 chan1_raw: 0_u16,
11029 chan2_raw: 0_u16,
11030 chan3_raw: 0_u16,
11031 chan4_raw: 0_u16,
11032 chan5_raw: 0_u16,
11033 chan6_raw: 0_u16,
11034 chan7_raw: 0_u16,
11035 chan8_raw: 0_u16,
11036 chan9_raw: 0_u16,
11037 chan10_raw: 0_u16,
11038 chan11_raw: 0_u16,
11039 chan12_raw: 0_u16,
11040 rssi: 0_u8,
11041 };
11042 #[cfg(feature = "arbitrary")]
11043 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11044 use arbitrary::{Arbitrary, Unstructured};
11045 let mut buf = [0u8; 1024];
11046 rng.fill_bytes(&mut buf);
11047 let mut unstructured = Unstructured::new(&buf);
11048 Self::arbitrary(&mut unstructured).unwrap_or_default()
11049 }
11050}
11051impl Default for HIL_RC_INPUTS_RAW_DATA {
11052 fn default() -> Self {
11053 Self::DEFAULT.clone()
11054 }
11055}
11056impl MessageData for HIL_RC_INPUTS_RAW_DATA {
11057 type Message = MavMessage;
11058 const ID: u32 = 92u32;
11059 const NAME: &'static str = "HIL_RC_INPUTS_RAW";
11060 const EXTRA_CRC: u8 = 54u8;
11061 const ENCODED_LEN: usize = 33usize;
11062 fn deser(
11063 _version: MavlinkVersion,
11064 __input: &[u8],
11065 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11066 let avail_len = __input.len();
11067 let mut payload_buf = [0; Self::ENCODED_LEN];
11068 let mut buf = if avail_len < Self::ENCODED_LEN {
11069 payload_buf[0..avail_len].copy_from_slice(__input);
11070 Bytes::new(&payload_buf)
11071 } else {
11072 Bytes::new(__input)
11073 };
11074 let mut __struct = Self::default();
11075 __struct.time_usec = buf.get_u64_le();
11076 __struct.chan1_raw = buf.get_u16_le();
11077 __struct.chan2_raw = buf.get_u16_le();
11078 __struct.chan3_raw = buf.get_u16_le();
11079 __struct.chan4_raw = buf.get_u16_le();
11080 __struct.chan5_raw = buf.get_u16_le();
11081 __struct.chan6_raw = buf.get_u16_le();
11082 __struct.chan7_raw = buf.get_u16_le();
11083 __struct.chan8_raw = buf.get_u16_le();
11084 __struct.chan9_raw = buf.get_u16_le();
11085 __struct.chan10_raw = buf.get_u16_le();
11086 __struct.chan11_raw = buf.get_u16_le();
11087 __struct.chan12_raw = buf.get_u16_le();
11088 __struct.rssi = buf.get_u8();
11089 Ok(__struct)
11090 }
11091 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11092 let mut __tmp = BytesMut::new(bytes);
11093 #[allow(clippy::absurd_extreme_comparisons)]
11094 #[allow(unused_comparisons)]
11095 if __tmp.remaining() < Self::ENCODED_LEN {
11096 panic!(
11097 "buffer is too small (need {} bytes, but got {})",
11098 Self::ENCODED_LEN,
11099 __tmp.remaining(),
11100 )
11101 }
11102 __tmp.put_u64_le(self.time_usec);
11103 __tmp.put_u16_le(self.chan1_raw);
11104 __tmp.put_u16_le(self.chan2_raw);
11105 __tmp.put_u16_le(self.chan3_raw);
11106 __tmp.put_u16_le(self.chan4_raw);
11107 __tmp.put_u16_le(self.chan5_raw);
11108 __tmp.put_u16_le(self.chan6_raw);
11109 __tmp.put_u16_le(self.chan7_raw);
11110 __tmp.put_u16_le(self.chan8_raw);
11111 __tmp.put_u16_le(self.chan9_raw);
11112 __tmp.put_u16_le(self.chan10_raw);
11113 __tmp.put_u16_le(self.chan11_raw);
11114 __tmp.put_u16_le(self.chan12_raw);
11115 __tmp.put_u8(self.rssi);
11116 if matches!(version, MavlinkVersion::V2) {
11117 let len = __tmp.len();
11118 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11119 } else {
11120 __tmp.len()
11121 }
11122 }
11123}
11124#[doc = "id: 375"]
11125#[doc = "The raw values of the actuator outputs (e.g. on Pixhawk, from MAIN, AUX ports). This message supersedes SERVO_OUTPUT_RAW."]
11126#[derive(Debug, Clone, PartialEq)]
11127#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11128#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11129pub struct ACTUATOR_OUTPUT_STATUS_DATA {
11130 #[doc = "Timestamp (since system boot)."]
11131 pub time_usec: u64,
11132 #[doc = "Active outputs"]
11133 pub active: u32,
11134 #[doc = "Servo / motor output array values. Zero values indicate unused channels."]
11135 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
11136 pub actuator: [f32; 32],
11137}
11138impl ACTUATOR_OUTPUT_STATUS_DATA {
11139 pub const ENCODED_LEN: usize = 140usize;
11140 pub const DEFAULT: Self = Self {
11141 time_usec: 0_u64,
11142 active: 0_u32,
11143 actuator: [0.0_f32; 32usize],
11144 };
11145 #[cfg(feature = "arbitrary")]
11146 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11147 use arbitrary::{Arbitrary, Unstructured};
11148 let mut buf = [0u8; 1024];
11149 rng.fill_bytes(&mut buf);
11150 let mut unstructured = Unstructured::new(&buf);
11151 Self::arbitrary(&mut unstructured).unwrap_or_default()
11152 }
11153}
11154impl Default for ACTUATOR_OUTPUT_STATUS_DATA {
11155 fn default() -> Self {
11156 Self::DEFAULT.clone()
11157 }
11158}
11159impl MessageData for ACTUATOR_OUTPUT_STATUS_DATA {
11160 type Message = MavMessage;
11161 const ID: u32 = 375u32;
11162 const NAME: &'static str = "ACTUATOR_OUTPUT_STATUS";
11163 const EXTRA_CRC: u8 = 251u8;
11164 const ENCODED_LEN: usize = 140usize;
11165 fn deser(
11166 _version: MavlinkVersion,
11167 __input: &[u8],
11168 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11169 let avail_len = __input.len();
11170 let mut payload_buf = [0; Self::ENCODED_LEN];
11171 let mut buf = if avail_len < Self::ENCODED_LEN {
11172 payload_buf[0..avail_len].copy_from_slice(__input);
11173 Bytes::new(&payload_buf)
11174 } else {
11175 Bytes::new(__input)
11176 };
11177 let mut __struct = Self::default();
11178 __struct.time_usec = buf.get_u64_le();
11179 __struct.active = buf.get_u32_le();
11180 for v in &mut __struct.actuator {
11181 let val = buf.get_f32_le();
11182 *v = val;
11183 }
11184 Ok(__struct)
11185 }
11186 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11187 let mut __tmp = BytesMut::new(bytes);
11188 #[allow(clippy::absurd_extreme_comparisons)]
11189 #[allow(unused_comparisons)]
11190 if __tmp.remaining() < Self::ENCODED_LEN {
11191 panic!(
11192 "buffer is too small (need {} bytes, but got {})",
11193 Self::ENCODED_LEN,
11194 __tmp.remaining(),
11195 )
11196 }
11197 __tmp.put_u64_le(self.time_usec);
11198 __tmp.put_u32_le(self.active);
11199 for val in &self.actuator {
11200 __tmp.put_f32_le(*val);
11201 }
11202 if matches!(version, MavlinkVersion::V2) {
11203 let len = __tmp.len();
11204 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11205 } else {
11206 __tmp.len()
11207 }
11208 }
11209}
11210#[doc = "id: 111"]
11211#[doc = "Time synchronization message. The message is used for both timesync requests and responses. The request is sent with `ts1=syncing component timestamp` and `tc1=0`, and may be broadcast or targeted to a specific system/component. The response is sent with `ts1=syncing component timestamp` (mirror back unchanged), and `tc1=responding component timestamp`, with the `target_system` and `target_component` set to ids of the original request. Systems can determine if they are receiving a request or response based on the value of `tc`. If the response has `target_system==target_component==0` the remote system has not been updated to use the component IDs and cannot reliably timesync; the requestor may report an error. Timestamps are UNIX Epoch time or time since system boot in nanoseconds (the timestamp format can be inferred by checking for the magnitude of the number; generally it doesn't matter as only the offset is used). The message sequence is repeated numerous times with results being filtered/averaged to estimate the offset. See also: <https://mavlink.io/en/services/timesync.html>."]
11212#[derive(Debug, Clone, PartialEq)]
11213#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11214#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11215pub struct TIMESYNC_DATA {
11216 #[doc = "Time sync timestamp 1. Syncing: 0. Responding: Timestamp of responding component."]
11217 pub tc1: i64,
11218 #[doc = "Time sync timestamp 2. Timestamp of syncing component (mirrored in response)."]
11219 pub ts1: i64,
11220 #[doc = "Target system id. Request: 0 (broadcast) or id of specific system. Response must contain system id of the requesting component."]
11221 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
11222 pub target_system: u8,
11223 #[doc = "Target component id. Request: 0 (broadcast) or id of specific component. Response must contain component id of the requesting component."]
11224 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
11225 pub target_component: u8,
11226}
11227impl TIMESYNC_DATA {
11228 pub const ENCODED_LEN: usize = 18usize;
11229 pub const DEFAULT: Self = Self {
11230 tc1: 0_i64,
11231 ts1: 0_i64,
11232 target_system: 0_u8,
11233 target_component: 0_u8,
11234 };
11235 #[cfg(feature = "arbitrary")]
11236 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11237 use arbitrary::{Arbitrary, Unstructured};
11238 let mut buf = [0u8; 1024];
11239 rng.fill_bytes(&mut buf);
11240 let mut unstructured = Unstructured::new(&buf);
11241 Self::arbitrary(&mut unstructured).unwrap_or_default()
11242 }
11243}
11244impl Default for TIMESYNC_DATA {
11245 fn default() -> Self {
11246 Self::DEFAULT.clone()
11247 }
11248}
11249impl MessageData for TIMESYNC_DATA {
11250 type Message = MavMessage;
11251 const ID: u32 = 111u32;
11252 const NAME: &'static str = "TIMESYNC";
11253 const EXTRA_CRC: u8 = 34u8;
11254 const ENCODED_LEN: usize = 18usize;
11255 fn deser(
11256 _version: MavlinkVersion,
11257 __input: &[u8],
11258 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11259 let avail_len = __input.len();
11260 let mut payload_buf = [0; Self::ENCODED_LEN];
11261 let mut buf = if avail_len < Self::ENCODED_LEN {
11262 payload_buf[0..avail_len].copy_from_slice(__input);
11263 Bytes::new(&payload_buf)
11264 } else {
11265 Bytes::new(__input)
11266 };
11267 let mut __struct = Self::default();
11268 __struct.tc1 = buf.get_i64_le();
11269 __struct.ts1 = buf.get_i64_le();
11270 __struct.target_system = buf.get_u8();
11271 __struct.target_component = buf.get_u8();
11272 Ok(__struct)
11273 }
11274 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11275 let mut __tmp = BytesMut::new(bytes);
11276 #[allow(clippy::absurd_extreme_comparisons)]
11277 #[allow(unused_comparisons)]
11278 if __tmp.remaining() < Self::ENCODED_LEN {
11279 panic!(
11280 "buffer is too small (need {} bytes, but got {})",
11281 Self::ENCODED_LEN,
11282 __tmp.remaining(),
11283 )
11284 }
11285 __tmp.put_i64_le(self.tc1);
11286 __tmp.put_i64_le(self.ts1);
11287 __tmp.put_u8(self.target_system);
11288 __tmp.put_u8(self.target_component);
11289 if matches!(version, MavlinkVersion::V2) {
11290 let len = __tmp.len();
11291 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11292 } else {
11293 __tmp.len()
11294 }
11295 }
11296}
11297#[doc = "id: 266"]
11298#[doc = "A message containing logged data (see also MAV_CMD_LOGGING_START)."]
11299#[derive(Debug, Clone, PartialEq)]
11300#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11301#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11302pub struct LOGGING_DATA_DATA {
11303 #[doc = "sequence number (can wrap)"]
11304 pub sequence: u16,
11305 #[doc = "system ID of the target"]
11306 pub target_system: u8,
11307 #[doc = "component ID of the target"]
11308 pub target_component: u8,
11309 #[doc = "data length"]
11310 pub length: u8,
11311 #[doc = "offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to UINT8_MAX if no start exists)."]
11312 pub first_message_offset: u8,
11313 #[doc = "logged data"]
11314 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
11315 pub data: [u8; 249],
11316}
11317impl LOGGING_DATA_DATA {
11318 pub const ENCODED_LEN: usize = 255usize;
11319 pub const DEFAULT: Self = Self {
11320 sequence: 0_u16,
11321 target_system: 0_u8,
11322 target_component: 0_u8,
11323 length: 0_u8,
11324 first_message_offset: 0_u8,
11325 data: [0_u8; 249usize],
11326 };
11327 #[cfg(feature = "arbitrary")]
11328 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11329 use arbitrary::{Arbitrary, Unstructured};
11330 let mut buf = [0u8; 1024];
11331 rng.fill_bytes(&mut buf);
11332 let mut unstructured = Unstructured::new(&buf);
11333 Self::arbitrary(&mut unstructured).unwrap_or_default()
11334 }
11335}
11336impl Default for LOGGING_DATA_DATA {
11337 fn default() -> Self {
11338 Self::DEFAULT.clone()
11339 }
11340}
11341impl MessageData for LOGGING_DATA_DATA {
11342 type Message = MavMessage;
11343 const ID: u32 = 266u32;
11344 const NAME: &'static str = "LOGGING_DATA";
11345 const EXTRA_CRC: u8 = 193u8;
11346 const ENCODED_LEN: usize = 255usize;
11347 fn deser(
11348 _version: MavlinkVersion,
11349 __input: &[u8],
11350 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11351 let avail_len = __input.len();
11352 let mut payload_buf = [0; Self::ENCODED_LEN];
11353 let mut buf = if avail_len < Self::ENCODED_LEN {
11354 payload_buf[0..avail_len].copy_from_slice(__input);
11355 Bytes::new(&payload_buf)
11356 } else {
11357 Bytes::new(__input)
11358 };
11359 let mut __struct = Self::default();
11360 __struct.sequence = buf.get_u16_le();
11361 __struct.target_system = buf.get_u8();
11362 __struct.target_component = buf.get_u8();
11363 __struct.length = buf.get_u8();
11364 __struct.first_message_offset = buf.get_u8();
11365 for v in &mut __struct.data {
11366 let val = buf.get_u8();
11367 *v = val;
11368 }
11369 Ok(__struct)
11370 }
11371 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11372 let mut __tmp = BytesMut::new(bytes);
11373 #[allow(clippy::absurd_extreme_comparisons)]
11374 #[allow(unused_comparisons)]
11375 if __tmp.remaining() < Self::ENCODED_LEN {
11376 panic!(
11377 "buffer is too small (need {} bytes, but got {})",
11378 Self::ENCODED_LEN,
11379 __tmp.remaining(),
11380 )
11381 }
11382 __tmp.put_u16_le(self.sequence);
11383 __tmp.put_u8(self.target_system);
11384 __tmp.put_u8(self.target_component);
11385 __tmp.put_u8(self.length);
11386 __tmp.put_u8(self.first_message_offset);
11387 for val in &self.data {
11388 __tmp.put_u8(*val);
11389 }
11390 if matches!(version, MavlinkVersion::V2) {
11391 let len = __tmp.len();
11392 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11393 } else {
11394 __tmp.len()
11395 }
11396 }
11397}
11398#[doc = "id: 388"]
11399#[doc = "Modify the filter of what CAN messages to forward over the mavlink. This can be used to make CAN forwarding work well on low bandwidth links. The filtering is applied on bits 8 to 24 of the CAN id (2nd and 3rd bytes) which corresponds to the DroneCAN message ID for DroneCAN. Filters with more than 16 IDs can be constructed by sending multiple CAN_FILTER_MODIFY messages."]
11400#[derive(Debug, Clone, PartialEq)]
11401#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11402#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11403pub struct CAN_FILTER_MODIFY_DATA {
11404 #[doc = "filter IDs, length num_ids"]
11405 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
11406 pub ids: [u16; 16],
11407 #[doc = "System ID."]
11408 pub target_system: u8,
11409 #[doc = "Component ID."]
11410 pub target_component: u8,
11411 #[doc = "bus number"]
11412 pub bus: u8,
11413 #[doc = "what operation to perform on the filter list. See CAN_FILTER_OP enum."]
11414 pub operation: CanFilterOp,
11415 #[doc = "number of IDs in filter list"]
11416 pub num_ids: u8,
11417}
11418impl CAN_FILTER_MODIFY_DATA {
11419 pub const ENCODED_LEN: usize = 37usize;
11420 pub const DEFAULT: Self = Self {
11421 ids: [0_u16; 16usize],
11422 target_system: 0_u8,
11423 target_component: 0_u8,
11424 bus: 0_u8,
11425 operation: CanFilterOp::DEFAULT,
11426 num_ids: 0_u8,
11427 };
11428 #[cfg(feature = "arbitrary")]
11429 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11430 use arbitrary::{Arbitrary, Unstructured};
11431 let mut buf = [0u8; 1024];
11432 rng.fill_bytes(&mut buf);
11433 let mut unstructured = Unstructured::new(&buf);
11434 Self::arbitrary(&mut unstructured).unwrap_or_default()
11435 }
11436}
11437impl Default for CAN_FILTER_MODIFY_DATA {
11438 fn default() -> Self {
11439 Self::DEFAULT.clone()
11440 }
11441}
11442impl MessageData for CAN_FILTER_MODIFY_DATA {
11443 type Message = MavMessage;
11444 const ID: u32 = 388u32;
11445 const NAME: &'static str = "CAN_FILTER_MODIFY";
11446 const EXTRA_CRC: u8 = 8u8;
11447 const ENCODED_LEN: usize = 37usize;
11448 fn deser(
11449 _version: MavlinkVersion,
11450 __input: &[u8],
11451 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11452 let avail_len = __input.len();
11453 let mut payload_buf = [0; Self::ENCODED_LEN];
11454 let mut buf = if avail_len < Self::ENCODED_LEN {
11455 payload_buf[0..avail_len].copy_from_slice(__input);
11456 Bytes::new(&payload_buf)
11457 } else {
11458 Bytes::new(__input)
11459 };
11460 let mut __struct = Self::default();
11461 for v in &mut __struct.ids {
11462 let val = buf.get_u16_le();
11463 *v = val;
11464 }
11465 __struct.target_system = buf.get_u8();
11466 __struct.target_component = buf.get_u8();
11467 __struct.bus = buf.get_u8();
11468 let tmp = buf.get_u8();
11469 __struct.operation =
11470 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
11471 enum_type: "CanFilterOp",
11472 value: tmp as u32,
11473 })?;
11474 __struct.num_ids = buf.get_u8();
11475 Ok(__struct)
11476 }
11477 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11478 let mut __tmp = BytesMut::new(bytes);
11479 #[allow(clippy::absurd_extreme_comparisons)]
11480 #[allow(unused_comparisons)]
11481 if __tmp.remaining() < Self::ENCODED_LEN {
11482 panic!(
11483 "buffer is too small (need {} bytes, but got {})",
11484 Self::ENCODED_LEN,
11485 __tmp.remaining(),
11486 )
11487 }
11488 for val in &self.ids {
11489 __tmp.put_u16_le(*val);
11490 }
11491 __tmp.put_u8(self.target_system);
11492 __tmp.put_u8(self.target_component);
11493 __tmp.put_u8(self.bus);
11494 __tmp.put_u8(self.operation as u8);
11495 __tmp.put_u8(self.num_ids);
11496 if matches!(version, MavlinkVersion::V2) {
11497 let len = __tmp.len();
11498 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11499 } else {
11500 __tmp.len()
11501 }
11502 }
11503}
11504#[doc = "id: 12920"]
11505#[doc = "Temperature and humidity from hygrometer."]
11506#[derive(Debug, Clone, PartialEq)]
11507#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11508#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11509pub struct HYGROMETER_SENSOR_DATA {
11510 #[doc = "Temperature"]
11511 pub temperature: i16,
11512 #[doc = "Humidity"]
11513 pub humidity: u16,
11514 #[doc = "Hygrometer ID"]
11515 pub id: u8,
11516}
11517impl HYGROMETER_SENSOR_DATA {
11518 pub const ENCODED_LEN: usize = 5usize;
11519 pub const DEFAULT: Self = Self {
11520 temperature: 0_i16,
11521 humidity: 0_u16,
11522 id: 0_u8,
11523 };
11524 #[cfg(feature = "arbitrary")]
11525 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11526 use arbitrary::{Arbitrary, Unstructured};
11527 let mut buf = [0u8; 1024];
11528 rng.fill_bytes(&mut buf);
11529 let mut unstructured = Unstructured::new(&buf);
11530 Self::arbitrary(&mut unstructured).unwrap_or_default()
11531 }
11532}
11533impl Default for HYGROMETER_SENSOR_DATA {
11534 fn default() -> Self {
11535 Self::DEFAULT.clone()
11536 }
11537}
11538impl MessageData for HYGROMETER_SENSOR_DATA {
11539 type Message = MavMessage;
11540 const ID: u32 = 12920u32;
11541 const NAME: &'static str = "HYGROMETER_SENSOR";
11542 const EXTRA_CRC: u8 = 20u8;
11543 const ENCODED_LEN: usize = 5usize;
11544 fn deser(
11545 _version: MavlinkVersion,
11546 __input: &[u8],
11547 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11548 let avail_len = __input.len();
11549 let mut payload_buf = [0; Self::ENCODED_LEN];
11550 let mut buf = if avail_len < Self::ENCODED_LEN {
11551 payload_buf[0..avail_len].copy_from_slice(__input);
11552 Bytes::new(&payload_buf)
11553 } else {
11554 Bytes::new(__input)
11555 };
11556 let mut __struct = Self::default();
11557 __struct.temperature = buf.get_i16_le();
11558 __struct.humidity = buf.get_u16_le();
11559 __struct.id = buf.get_u8();
11560 Ok(__struct)
11561 }
11562 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11563 let mut __tmp = BytesMut::new(bytes);
11564 #[allow(clippy::absurd_extreme_comparisons)]
11565 #[allow(unused_comparisons)]
11566 if __tmp.remaining() < Self::ENCODED_LEN {
11567 panic!(
11568 "buffer is too small (need {} bytes, but got {})",
11569 Self::ENCODED_LEN,
11570 __tmp.remaining(),
11571 )
11572 }
11573 __tmp.put_i16_le(self.temperature);
11574 __tmp.put_u16_le(self.humidity);
11575 __tmp.put_u8(self.id);
11576 if matches!(version, MavlinkVersion::V2) {
11577 let len = __tmp.len();
11578 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11579 } else {
11580 __tmp.len()
11581 }
11582 }
11583}
11584#[doc = "id: 372"]
11585#[doc = "Battery information that is static, or requires infrequent update. This message should requested using MAV_CMD_REQUEST_MESSAGE and/or streamed at very low rate. BATTERY_STATUS_V2 is used for higher-rate battery status information."]
11586#[derive(Debug, Clone, PartialEq)]
11587#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11588#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11589pub struct BATTERY_INFO_DATA {
11590 #[doc = "Minimum per-cell voltage when discharging. 0: field not provided."]
11591 pub discharge_minimum_voltage: f32,
11592 #[doc = "Minimum per-cell voltage when charging. 0: field not provided."]
11593 pub charging_minimum_voltage: f32,
11594 #[doc = "Minimum per-cell voltage when resting. 0: field not provided."]
11595 pub resting_minimum_voltage: f32,
11596 #[doc = "Maximum per-cell voltage when charged. 0: field not provided."]
11597 pub charging_maximum_voltage: f32,
11598 #[doc = "Maximum pack continuous charge current. 0: field not provided."]
11599 pub charging_maximum_current: f32,
11600 #[doc = "Battery nominal voltage. Used for conversion between Wh and Ah. 0: field not provided."]
11601 pub nominal_voltage: f32,
11602 #[doc = "Maximum pack discharge current. 0: field not provided."]
11603 pub discharge_maximum_current: f32,
11604 #[doc = "Maximum pack discharge burst current. 0: field not provided."]
11605 pub discharge_maximum_burst_current: f32,
11606 #[doc = "Fully charged design capacity. 0: field not provided."]
11607 pub design_capacity: f32,
11608 #[doc = "Predicted battery capacity when fully charged (accounting for battery degradation). NAN: field not provided."]
11609 pub full_charge_capacity: f32,
11610 #[doc = "Lifetime count of the number of charge/discharge cycles (<https://en.wikipedia.org/wiki/Charge_cycle>). UINT16_MAX: field not provided."]
11611 pub cycle_count: u16,
11612 #[doc = "Battery weight. 0: field not provided."]
11613 pub weight: u16,
11614 #[doc = "Battery ID"]
11615 pub id: u8,
11616 #[doc = "Function of the battery."]
11617 pub battery_function: MavBatteryFunction,
11618 #[doc = "Type (chemistry) of the battery."]
11619 pub mavtype: MavBatteryType,
11620 #[doc = "State of Health (SOH) estimate. Typically 100% at the time of manufacture and will decrease over time and use. -1: field not provided."]
11621 pub state_of_health: u8,
11622 #[doc = "Number of battery cells in series. 0: field not provided."]
11623 pub cells_in_series: u8,
11624 #[doc = "Manufacture date (DDMMYYYY) in ASCII characters, 0 terminated. All 0: field not provided."]
11625 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
11626 pub manufacture_date: [u8; 9],
11627 #[doc = "Serial number in ASCII characters, 0 terminated. All 0: field not provided."]
11628 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
11629 pub serial_number: [u8; 32],
11630 #[doc = "Battery device name. Formatted as manufacturer name then product name, separated with an underscore (in ASCII characters), 0 terminated. All 0: field not provided."]
11631 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
11632 pub name: [u8; 50],
11633}
11634impl BATTERY_INFO_DATA {
11635 pub const ENCODED_LEN: usize = 140usize;
11636 pub const DEFAULT: Self = Self {
11637 discharge_minimum_voltage: 0.0_f32,
11638 charging_minimum_voltage: 0.0_f32,
11639 resting_minimum_voltage: 0.0_f32,
11640 charging_maximum_voltage: 0.0_f32,
11641 charging_maximum_current: 0.0_f32,
11642 nominal_voltage: 0.0_f32,
11643 discharge_maximum_current: 0.0_f32,
11644 discharge_maximum_burst_current: 0.0_f32,
11645 design_capacity: 0.0_f32,
11646 full_charge_capacity: 0.0_f32,
11647 cycle_count: 0_u16,
11648 weight: 0_u16,
11649 id: 0_u8,
11650 battery_function: MavBatteryFunction::DEFAULT,
11651 mavtype: MavBatteryType::DEFAULT,
11652 state_of_health: 0_u8,
11653 cells_in_series: 0_u8,
11654 manufacture_date: [0_u8; 9usize],
11655 serial_number: [0_u8; 32usize],
11656 name: [0_u8; 50usize],
11657 };
11658 #[cfg(feature = "arbitrary")]
11659 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11660 use arbitrary::{Arbitrary, Unstructured};
11661 let mut buf = [0u8; 1024];
11662 rng.fill_bytes(&mut buf);
11663 let mut unstructured = Unstructured::new(&buf);
11664 Self::arbitrary(&mut unstructured).unwrap_or_default()
11665 }
11666}
11667impl Default for BATTERY_INFO_DATA {
11668 fn default() -> Self {
11669 Self::DEFAULT.clone()
11670 }
11671}
11672impl MessageData for BATTERY_INFO_DATA {
11673 type Message = MavMessage;
11674 const ID: u32 = 372u32;
11675 const NAME: &'static str = "BATTERY_INFO";
11676 const EXTRA_CRC: u8 = 26u8;
11677 const ENCODED_LEN: usize = 140usize;
11678 fn deser(
11679 _version: MavlinkVersion,
11680 __input: &[u8],
11681 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11682 let avail_len = __input.len();
11683 let mut payload_buf = [0; Self::ENCODED_LEN];
11684 let mut buf = if avail_len < Self::ENCODED_LEN {
11685 payload_buf[0..avail_len].copy_from_slice(__input);
11686 Bytes::new(&payload_buf)
11687 } else {
11688 Bytes::new(__input)
11689 };
11690 let mut __struct = Self::default();
11691 __struct.discharge_minimum_voltage = buf.get_f32_le();
11692 __struct.charging_minimum_voltage = buf.get_f32_le();
11693 __struct.resting_minimum_voltage = buf.get_f32_le();
11694 __struct.charging_maximum_voltage = buf.get_f32_le();
11695 __struct.charging_maximum_current = buf.get_f32_le();
11696 __struct.nominal_voltage = buf.get_f32_le();
11697 __struct.discharge_maximum_current = buf.get_f32_le();
11698 __struct.discharge_maximum_burst_current = buf.get_f32_le();
11699 __struct.design_capacity = buf.get_f32_le();
11700 __struct.full_charge_capacity = buf.get_f32_le();
11701 __struct.cycle_count = buf.get_u16_le();
11702 __struct.weight = buf.get_u16_le();
11703 __struct.id = buf.get_u8();
11704 let tmp = buf.get_u8();
11705 __struct.battery_function =
11706 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
11707 enum_type: "MavBatteryFunction",
11708 value: tmp as u32,
11709 })?;
11710 let tmp = buf.get_u8();
11711 __struct.mavtype =
11712 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
11713 enum_type: "MavBatteryType",
11714 value: tmp as u32,
11715 })?;
11716 __struct.state_of_health = buf.get_u8();
11717 __struct.cells_in_series = buf.get_u8();
11718 for v in &mut __struct.manufacture_date {
11719 let val = buf.get_u8();
11720 *v = val;
11721 }
11722 for v in &mut __struct.serial_number {
11723 let val = buf.get_u8();
11724 *v = val;
11725 }
11726 for v in &mut __struct.name {
11727 let val = buf.get_u8();
11728 *v = val;
11729 }
11730 Ok(__struct)
11731 }
11732 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11733 let mut __tmp = BytesMut::new(bytes);
11734 #[allow(clippy::absurd_extreme_comparisons)]
11735 #[allow(unused_comparisons)]
11736 if __tmp.remaining() < Self::ENCODED_LEN {
11737 panic!(
11738 "buffer is too small (need {} bytes, but got {})",
11739 Self::ENCODED_LEN,
11740 __tmp.remaining(),
11741 )
11742 }
11743 __tmp.put_f32_le(self.discharge_minimum_voltage);
11744 __tmp.put_f32_le(self.charging_minimum_voltage);
11745 __tmp.put_f32_le(self.resting_minimum_voltage);
11746 __tmp.put_f32_le(self.charging_maximum_voltage);
11747 __tmp.put_f32_le(self.charging_maximum_current);
11748 __tmp.put_f32_le(self.nominal_voltage);
11749 __tmp.put_f32_le(self.discharge_maximum_current);
11750 __tmp.put_f32_le(self.discharge_maximum_burst_current);
11751 __tmp.put_f32_le(self.design_capacity);
11752 __tmp.put_f32_le(self.full_charge_capacity);
11753 __tmp.put_u16_le(self.cycle_count);
11754 __tmp.put_u16_le(self.weight);
11755 __tmp.put_u8(self.id);
11756 __tmp.put_u8(self.battery_function as u8);
11757 __tmp.put_u8(self.mavtype as u8);
11758 __tmp.put_u8(self.state_of_health);
11759 __tmp.put_u8(self.cells_in_series);
11760 for val in &self.manufacture_date {
11761 __tmp.put_u8(*val);
11762 }
11763 for val in &self.serial_number {
11764 __tmp.put_u8(*val);
11765 }
11766 for val in &self.name {
11767 __tmp.put_u8(*val);
11768 }
11769 if matches!(version, MavlinkVersion::V2) {
11770 let len = __tmp.len();
11771 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11772 } else {
11773 __tmp.len()
11774 }
11775 }
11776}
11777#[doc = "id: 323"]
11778#[doc = "Set a parameter value. In order to deal with message loss (and retransmission of PARAM_EXT_SET), when setting a parameter value and the new value is the same as the current value, you will immediately get a PARAM_ACK_ACCEPTED response. If the current state is PARAM_ACK_IN_PROGRESS, you will accordingly receive a PARAM_ACK_IN_PROGRESS in response."]
11779#[derive(Debug, Clone, PartialEq)]
11780#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11781#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11782pub struct PARAM_EXT_SET_DATA {
11783 #[doc = "System ID"]
11784 pub target_system: u8,
11785 #[doc = "Component ID"]
11786 pub target_component: u8,
11787 #[doc = "Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string"]
11788 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
11789 pub param_id: [u8; 16],
11790 #[doc = "Parameter value"]
11791 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
11792 pub param_value: [u8; 128],
11793 #[doc = "Parameter type."]
11794 pub param_type: MavParamExtType,
11795}
11796impl PARAM_EXT_SET_DATA {
11797 pub const ENCODED_LEN: usize = 147usize;
11798 pub const DEFAULT: Self = Self {
11799 target_system: 0_u8,
11800 target_component: 0_u8,
11801 param_id: [0_u8; 16usize],
11802 param_value: [0_u8; 128usize],
11803 param_type: MavParamExtType::DEFAULT,
11804 };
11805 #[cfg(feature = "arbitrary")]
11806 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11807 use arbitrary::{Arbitrary, Unstructured};
11808 let mut buf = [0u8; 1024];
11809 rng.fill_bytes(&mut buf);
11810 let mut unstructured = Unstructured::new(&buf);
11811 Self::arbitrary(&mut unstructured).unwrap_or_default()
11812 }
11813}
11814impl Default for PARAM_EXT_SET_DATA {
11815 fn default() -> Self {
11816 Self::DEFAULT.clone()
11817 }
11818}
11819impl MessageData for PARAM_EXT_SET_DATA {
11820 type Message = MavMessage;
11821 const ID: u32 = 323u32;
11822 const NAME: &'static str = "PARAM_EXT_SET";
11823 const EXTRA_CRC: u8 = 78u8;
11824 const ENCODED_LEN: usize = 147usize;
11825 fn deser(
11826 _version: MavlinkVersion,
11827 __input: &[u8],
11828 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11829 let avail_len = __input.len();
11830 let mut payload_buf = [0; Self::ENCODED_LEN];
11831 let mut buf = if avail_len < Self::ENCODED_LEN {
11832 payload_buf[0..avail_len].copy_from_slice(__input);
11833 Bytes::new(&payload_buf)
11834 } else {
11835 Bytes::new(__input)
11836 };
11837 let mut __struct = Self::default();
11838 __struct.target_system = buf.get_u8();
11839 __struct.target_component = buf.get_u8();
11840 for v in &mut __struct.param_id {
11841 let val = buf.get_u8();
11842 *v = val;
11843 }
11844 for v in &mut __struct.param_value {
11845 let val = buf.get_u8();
11846 *v = val;
11847 }
11848 let tmp = buf.get_u8();
11849 __struct.param_type =
11850 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
11851 enum_type: "MavParamExtType",
11852 value: tmp as u32,
11853 })?;
11854 Ok(__struct)
11855 }
11856 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11857 let mut __tmp = BytesMut::new(bytes);
11858 #[allow(clippy::absurd_extreme_comparisons)]
11859 #[allow(unused_comparisons)]
11860 if __tmp.remaining() < Self::ENCODED_LEN {
11861 panic!(
11862 "buffer is too small (need {} bytes, but got {})",
11863 Self::ENCODED_LEN,
11864 __tmp.remaining(),
11865 )
11866 }
11867 __tmp.put_u8(self.target_system);
11868 __tmp.put_u8(self.target_component);
11869 for val in &self.param_id {
11870 __tmp.put_u8(*val);
11871 }
11872 for val in &self.param_value {
11873 __tmp.put_u8(*val);
11874 }
11875 __tmp.put_u8(self.param_type as u8);
11876 if matches!(version, MavlinkVersion::V2) {
11877 let len = __tmp.len();
11878 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11879 } else {
11880 __tmp.len()
11881 }
11882 }
11883}
11884#[doc = "id: 55"]
11885#[doc = "Read out the safety zone the MAV currently assumes."]
11886#[derive(Debug, Clone, PartialEq)]
11887#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11888#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11889pub struct SAFETY_ALLOWED_AREA_DATA {
11890 #[doc = "x position 1 / Latitude 1"]
11891 pub p1x: f32,
11892 #[doc = "y position 1 / Longitude 1"]
11893 pub p1y: f32,
11894 #[doc = "z position 1 / Altitude 1"]
11895 pub p1z: f32,
11896 #[doc = "x position 2 / Latitude 2"]
11897 pub p2x: f32,
11898 #[doc = "y position 2 / Longitude 2"]
11899 pub p2y: f32,
11900 #[doc = "z position 2 / Altitude 2"]
11901 pub p2z: f32,
11902 #[doc = "Coordinate frame. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down."]
11903 pub frame: MavFrame,
11904}
11905impl SAFETY_ALLOWED_AREA_DATA {
11906 pub const ENCODED_LEN: usize = 25usize;
11907 pub const DEFAULT: Self = Self {
11908 p1x: 0.0_f32,
11909 p1y: 0.0_f32,
11910 p1z: 0.0_f32,
11911 p2x: 0.0_f32,
11912 p2y: 0.0_f32,
11913 p2z: 0.0_f32,
11914 frame: MavFrame::DEFAULT,
11915 };
11916 #[cfg(feature = "arbitrary")]
11917 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11918 use arbitrary::{Arbitrary, Unstructured};
11919 let mut buf = [0u8; 1024];
11920 rng.fill_bytes(&mut buf);
11921 let mut unstructured = Unstructured::new(&buf);
11922 Self::arbitrary(&mut unstructured).unwrap_or_default()
11923 }
11924}
11925impl Default for SAFETY_ALLOWED_AREA_DATA {
11926 fn default() -> Self {
11927 Self::DEFAULT.clone()
11928 }
11929}
11930impl MessageData for SAFETY_ALLOWED_AREA_DATA {
11931 type Message = MavMessage;
11932 const ID: u32 = 55u32;
11933 const NAME: &'static str = "SAFETY_ALLOWED_AREA";
11934 const EXTRA_CRC: u8 = 3u8;
11935 const ENCODED_LEN: usize = 25usize;
11936 fn deser(
11937 _version: MavlinkVersion,
11938 __input: &[u8],
11939 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11940 let avail_len = __input.len();
11941 let mut payload_buf = [0; Self::ENCODED_LEN];
11942 let mut buf = if avail_len < Self::ENCODED_LEN {
11943 payload_buf[0..avail_len].copy_from_slice(__input);
11944 Bytes::new(&payload_buf)
11945 } else {
11946 Bytes::new(__input)
11947 };
11948 let mut __struct = Self::default();
11949 __struct.p1x = buf.get_f32_le();
11950 __struct.p1y = buf.get_f32_le();
11951 __struct.p1z = buf.get_f32_le();
11952 __struct.p2x = buf.get_f32_le();
11953 __struct.p2y = buf.get_f32_le();
11954 __struct.p2z = buf.get_f32_le();
11955 let tmp = buf.get_u8();
11956 __struct.frame =
11957 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
11958 enum_type: "MavFrame",
11959 value: tmp as u32,
11960 })?;
11961 Ok(__struct)
11962 }
11963 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11964 let mut __tmp = BytesMut::new(bytes);
11965 #[allow(clippy::absurd_extreme_comparisons)]
11966 #[allow(unused_comparisons)]
11967 if __tmp.remaining() < Self::ENCODED_LEN {
11968 panic!(
11969 "buffer is too small (need {} bytes, but got {})",
11970 Self::ENCODED_LEN,
11971 __tmp.remaining(),
11972 )
11973 }
11974 __tmp.put_f32_le(self.p1x);
11975 __tmp.put_f32_le(self.p1y);
11976 __tmp.put_f32_le(self.p1z);
11977 __tmp.put_f32_le(self.p2x);
11978 __tmp.put_f32_le(self.p2y);
11979 __tmp.put_f32_le(self.p2z);
11980 __tmp.put_u8(self.frame as u8);
11981 if matches!(version, MavlinkVersion::V2) {
11982 let len = __tmp.len();
11983 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11984 } else {
11985 __tmp.len()
11986 }
11987 }
11988}
11989#[doc = "id: 225"]
11990#[doc = "EFI status output."]
11991#[derive(Debug, Clone, PartialEq)]
11992#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11993#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11994pub struct EFI_STATUS_DATA {
11995 #[doc = "ECU index"]
11996 pub ecu_index: f32,
11997 #[doc = "RPM"]
11998 pub rpm: f32,
11999 #[doc = "Fuel consumed"]
12000 pub fuel_consumed: f32,
12001 #[doc = "Fuel flow rate"]
12002 pub fuel_flow: f32,
12003 #[doc = "Engine load"]
12004 pub engine_load: f32,
12005 #[doc = "Throttle position"]
12006 pub throttle_position: f32,
12007 #[doc = "Spark dwell time"]
12008 pub spark_dwell_time: f32,
12009 #[doc = "Barometric pressure"]
12010 pub barometric_pressure: f32,
12011 #[doc = "Intake manifold pressure("]
12012 pub intake_manifold_pressure: f32,
12013 #[doc = "Intake manifold temperature"]
12014 pub intake_manifold_temperature: f32,
12015 #[doc = "Cylinder head temperature"]
12016 pub cylinder_head_temperature: f32,
12017 #[doc = "Ignition timing (Crank angle degrees)"]
12018 pub ignition_timing: f32,
12019 #[doc = "Injection time"]
12020 pub injection_time: f32,
12021 #[doc = "Exhaust gas temperature"]
12022 pub exhaust_gas_temperature: f32,
12023 #[doc = "Output throttle"]
12024 pub throttle_out: f32,
12025 #[doc = "Pressure/temperature compensation"]
12026 pub pt_compensation: f32,
12027 #[doc = "EFI health status"]
12028 pub health: u8,
12029 #[doc = "Supply voltage to EFI sparking system. Zero in this value means \"unknown\", so if the supply voltage really is zero volts use 0.0001 instead."]
12030 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
12031 pub ignition_voltage: f32,
12032 #[doc = "Fuel pressure. Zero in this value means \"unknown\", so if the fuel pressure really is zero kPa use 0.0001 instead."]
12033 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
12034 pub fuel_pressure: f32,
12035}
12036impl EFI_STATUS_DATA {
12037 pub const ENCODED_LEN: usize = 73usize;
12038 pub const DEFAULT: Self = Self {
12039 ecu_index: 0.0_f32,
12040 rpm: 0.0_f32,
12041 fuel_consumed: 0.0_f32,
12042 fuel_flow: 0.0_f32,
12043 engine_load: 0.0_f32,
12044 throttle_position: 0.0_f32,
12045 spark_dwell_time: 0.0_f32,
12046 barometric_pressure: 0.0_f32,
12047 intake_manifold_pressure: 0.0_f32,
12048 intake_manifold_temperature: 0.0_f32,
12049 cylinder_head_temperature: 0.0_f32,
12050 ignition_timing: 0.0_f32,
12051 injection_time: 0.0_f32,
12052 exhaust_gas_temperature: 0.0_f32,
12053 throttle_out: 0.0_f32,
12054 pt_compensation: 0.0_f32,
12055 health: 0_u8,
12056 ignition_voltage: 0.0_f32,
12057 fuel_pressure: 0.0_f32,
12058 };
12059 #[cfg(feature = "arbitrary")]
12060 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12061 use arbitrary::{Arbitrary, Unstructured};
12062 let mut buf = [0u8; 1024];
12063 rng.fill_bytes(&mut buf);
12064 let mut unstructured = Unstructured::new(&buf);
12065 Self::arbitrary(&mut unstructured).unwrap_or_default()
12066 }
12067}
12068impl Default for EFI_STATUS_DATA {
12069 fn default() -> Self {
12070 Self::DEFAULT.clone()
12071 }
12072}
12073impl MessageData for EFI_STATUS_DATA {
12074 type Message = MavMessage;
12075 const ID: u32 = 225u32;
12076 const NAME: &'static str = "EFI_STATUS";
12077 const EXTRA_CRC: u8 = 208u8;
12078 const ENCODED_LEN: usize = 73usize;
12079 fn deser(
12080 _version: MavlinkVersion,
12081 __input: &[u8],
12082 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12083 let avail_len = __input.len();
12084 let mut payload_buf = [0; Self::ENCODED_LEN];
12085 let mut buf = if avail_len < Self::ENCODED_LEN {
12086 payload_buf[0..avail_len].copy_from_slice(__input);
12087 Bytes::new(&payload_buf)
12088 } else {
12089 Bytes::new(__input)
12090 };
12091 let mut __struct = Self::default();
12092 __struct.ecu_index = buf.get_f32_le();
12093 __struct.rpm = buf.get_f32_le();
12094 __struct.fuel_consumed = buf.get_f32_le();
12095 __struct.fuel_flow = buf.get_f32_le();
12096 __struct.engine_load = buf.get_f32_le();
12097 __struct.throttle_position = buf.get_f32_le();
12098 __struct.spark_dwell_time = buf.get_f32_le();
12099 __struct.barometric_pressure = buf.get_f32_le();
12100 __struct.intake_manifold_pressure = buf.get_f32_le();
12101 __struct.intake_manifold_temperature = buf.get_f32_le();
12102 __struct.cylinder_head_temperature = buf.get_f32_le();
12103 __struct.ignition_timing = buf.get_f32_le();
12104 __struct.injection_time = buf.get_f32_le();
12105 __struct.exhaust_gas_temperature = buf.get_f32_le();
12106 __struct.throttle_out = buf.get_f32_le();
12107 __struct.pt_compensation = buf.get_f32_le();
12108 __struct.health = buf.get_u8();
12109 __struct.ignition_voltage = buf.get_f32_le();
12110 __struct.fuel_pressure = buf.get_f32_le();
12111 Ok(__struct)
12112 }
12113 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12114 let mut __tmp = BytesMut::new(bytes);
12115 #[allow(clippy::absurd_extreme_comparisons)]
12116 #[allow(unused_comparisons)]
12117 if __tmp.remaining() < Self::ENCODED_LEN {
12118 panic!(
12119 "buffer is too small (need {} bytes, but got {})",
12120 Self::ENCODED_LEN,
12121 __tmp.remaining(),
12122 )
12123 }
12124 __tmp.put_f32_le(self.ecu_index);
12125 __tmp.put_f32_le(self.rpm);
12126 __tmp.put_f32_le(self.fuel_consumed);
12127 __tmp.put_f32_le(self.fuel_flow);
12128 __tmp.put_f32_le(self.engine_load);
12129 __tmp.put_f32_le(self.throttle_position);
12130 __tmp.put_f32_le(self.spark_dwell_time);
12131 __tmp.put_f32_le(self.barometric_pressure);
12132 __tmp.put_f32_le(self.intake_manifold_pressure);
12133 __tmp.put_f32_le(self.intake_manifold_temperature);
12134 __tmp.put_f32_le(self.cylinder_head_temperature);
12135 __tmp.put_f32_le(self.ignition_timing);
12136 __tmp.put_f32_le(self.injection_time);
12137 __tmp.put_f32_le(self.exhaust_gas_temperature);
12138 __tmp.put_f32_le(self.throttle_out);
12139 __tmp.put_f32_le(self.pt_compensation);
12140 __tmp.put_u8(self.health);
12141 __tmp.put_f32_le(self.ignition_voltage);
12142 __tmp.put_f32_le(self.fuel_pressure);
12143 if matches!(version, MavlinkVersion::V2) {
12144 let len = __tmp.len();
12145 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12146 } else {
12147 __tmp.len()
12148 }
12149 }
12150}
12151#[doc = "id: 148"]
12152#[doc = "Version and capability of autopilot software. This should be emitted in response to a request with MAV_CMD_REQUEST_MESSAGE."]
12153#[derive(Debug, Clone, PartialEq)]
12154#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12155#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12156pub struct AUTOPILOT_VERSION_DATA {
12157 #[doc = "Bitmap of capabilities"]
12158 pub capabilities: MavProtocolCapability,
12159 #[doc = "UID if provided by hardware (see uid2)"]
12160 pub uid: u64,
12161 #[doc = "Firmware version number. The field must be encoded as 4 bytes, where each byte (shown from MSB to LSB) is part of a semantic version: (major) (minor) (patch) (FIRMWARE_VERSION_TYPE)."]
12162 pub flight_sw_version: u32,
12163 #[doc = "Middleware version number"]
12164 pub middleware_sw_version: u32,
12165 #[doc = "Operating system version number"]
12166 pub os_sw_version: u32,
12167 #[doc = "HW / board version (last 8 bits should be silicon ID, if any). The first 16 bits of this field specify <https://github.com/PX4/PX4-Bootloader/blob/master/board_types.txt>"]
12168 pub board_version: u32,
12169 #[doc = "ID of the board vendor"]
12170 pub vendor_id: u16,
12171 #[doc = "ID of the product"]
12172 pub product_id: u16,
12173 #[doc = "Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases."]
12174 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
12175 pub flight_custom_version: [u8; 8],
12176 #[doc = "Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases."]
12177 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
12178 pub middleware_custom_version: [u8; 8],
12179 #[doc = "Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases."]
12180 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
12181 pub os_custom_version: [u8; 8],
12182 #[doc = "UID if provided by hardware (supersedes the uid field. If this is non-zero, use this field, otherwise use uid)"]
12183 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
12184 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
12185 pub uid2: [u8; 18],
12186}
12187impl AUTOPILOT_VERSION_DATA {
12188 pub const ENCODED_LEN: usize = 78usize;
12189 pub const DEFAULT: Self = Self {
12190 capabilities: MavProtocolCapability::DEFAULT,
12191 uid: 0_u64,
12192 flight_sw_version: 0_u32,
12193 middleware_sw_version: 0_u32,
12194 os_sw_version: 0_u32,
12195 board_version: 0_u32,
12196 vendor_id: 0_u16,
12197 product_id: 0_u16,
12198 flight_custom_version: [0_u8; 8usize],
12199 middleware_custom_version: [0_u8; 8usize],
12200 os_custom_version: [0_u8; 8usize],
12201 uid2: [0_u8; 18usize],
12202 };
12203 #[cfg(feature = "arbitrary")]
12204 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12205 use arbitrary::{Arbitrary, Unstructured};
12206 let mut buf = [0u8; 1024];
12207 rng.fill_bytes(&mut buf);
12208 let mut unstructured = Unstructured::new(&buf);
12209 Self::arbitrary(&mut unstructured).unwrap_or_default()
12210 }
12211}
12212impl Default for AUTOPILOT_VERSION_DATA {
12213 fn default() -> Self {
12214 Self::DEFAULT.clone()
12215 }
12216}
12217impl MessageData for AUTOPILOT_VERSION_DATA {
12218 type Message = MavMessage;
12219 const ID: u32 = 148u32;
12220 const NAME: &'static str = "AUTOPILOT_VERSION";
12221 const EXTRA_CRC: u8 = 178u8;
12222 const ENCODED_LEN: usize = 78usize;
12223 fn deser(
12224 _version: MavlinkVersion,
12225 __input: &[u8],
12226 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12227 let avail_len = __input.len();
12228 let mut payload_buf = [0; Self::ENCODED_LEN];
12229 let mut buf = if avail_len < Self::ENCODED_LEN {
12230 payload_buf[0..avail_len].copy_from_slice(__input);
12231 Bytes::new(&payload_buf)
12232 } else {
12233 Bytes::new(__input)
12234 };
12235 let mut __struct = Self::default();
12236 let tmp = buf.get_u64_le();
12237 __struct.capabilities = MavProtocolCapability::from_bits(
12238 tmp & MavProtocolCapability::all().bits(),
12239 )
12240 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
12241 flag_type: "MavProtocolCapability",
12242 value: tmp as u32,
12243 })?;
12244 __struct.uid = buf.get_u64_le();
12245 __struct.flight_sw_version = buf.get_u32_le();
12246 __struct.middleware_sw_version = buf.get_u32_le();
12247 __struct.os_sw_version = buf.get_u32_le();
12248 __struct.board_version = buf.get_u32_le();
12249 __struct.vendor_id = buf.get_u16_le();
12250 __struct.product_id = buf.get_u16_le();
12251 for v in &mut __struct.flight_custom_version {
12252 let val = buf.get_u8();
12253 *v = val;
12254 }
12255 for v in &mut __struct.middleware_custom_version {
12256 let val = buf.get_u8();
12257 *v = val;
12258 }
12259 for v in &mut __struct.os_custom_version {
12260 let val = buf.get_u8();
12261 *v = val;
12262 }
12263 for v in &mut __struct.uid2 {
12264 let val = buf.get_u8();
12265 *v = val;
12266 }
12267 Ok(__struct)
12268 }
12269 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12270 let mut __tmp = BytesMut::new(bytes);
12271 #[allow(clippy::absurd_extreme_comparisons)]
12272 #[allow(unused_comparisons)]
12273 if __tmp.remaining() < Self::ENCODED_LEN {
12274 panic!(
12275 "buffer is too small (need {} bytes, but got {})",
12276 Self::ENCODED_LEN,
12277 __tmp.remaining(),
12278 )
12279 }
12280 __tmp.put_u64_le(self.capabilities.bits());
12281 __tmp.put_u64_le(self.uid);
12282 __tmp.put_u32_le(self.flight_sw_version);
12283 __tmp.put_u32_le(self.middleware_sw_version);
12284 __tmp.put_u32_le(self.os_sw_version);
12285 __tmp.put_u32_le(self.board_version);
12286 __tmp.put_u16_le(self.vendor_id);
12287 __tmp.put_u16_le(self.product_id);
12288 for val in &self.flight_custom_version {
12289 __tmp.put_u8(*val);
12290 }
12291 for val in &self.middleware_custom_version {
12292 __tmp.put_u8(*val);
12293 }
12294 for val in &self.os_custom_version {
12295 __tmp.put_u8(*val);
12296 }
12297 for val in &self.uid2 {
12298 __tmp.put_u8(*val);
12299 }
12300 if matches!(version, MavlinkVersion::V2) {
12301 let len = __tmp.len();
12302 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12303 } else {
12304 __tmp.len()
12305 }
12306 }
12307}
12308#[doc = "id: 11"]
12309#[doc = "Set the system mode, as defined by enum MAV_MODE. There is no target component id as the mode is by definition for the overall aircraft, not only for one component."]
12310#[derive(Debug, Clone, PartialEq)]
12311#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12312#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12313pub struct SET_MODE_DATA {
12314 #[doc = "The new autopilot-specific mode. This field can be ignored by an autopilot."]
12315 pub custom_mode: u32,
12316 #[doc = "The system setting the mode"]
12317 pub target_system: u8,
12318 #[doc = "The new base mode."]
12319 pub base_mode: MavMode,
12320}
12321impl SET_MODE_DATA {
12322 pub const ENCODED_LEN: usize = 6usize;
12323 pub const DEFAULT: Self = Self {
12324 custom_mode: 0_u32,
12325 target_system: 0_u8,
12326 base_mode: MavMode::DEFAULT,
12327 };
12328 #[cfg(feature = "arbitrary")]
12329 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12330 use arbitrary::{Arbitrary, Unstructured};
12331 let mut buf = [0u8; 1024];
12332 rng.fill_bytes(&mut buf);
12333 let mut unstructured = Unstructured::new(&buf);
12334 Self::arbitrary(&mut unstructured).unwrap_or_default()
12335 }
12336}
12337impl Default for SET_MODE_DATA {
12338 fn default() -> Self {
12339 Self::DEFAULT.clone()
12340 }
12341}
12342impl MessageData for SET_MODE_DATA {
12343 type Message = MavMessage;
12344 const ID: u32 = 11u32;
12345 const NAME: &'static str = "SET_MODE";
12346 const EXTRA_CRC: u8 = 89u8;
12347 const ENCODED_LEN: usize = 6usize;
12348 fn deser(
12349 _version: MavlinkVersion,
12350 __input: &[u8],
12351 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12352 let avail_len = __input.len();
12353 let mut payload_buf = [0; Self::ENCODED_LEN];
12354 let mut buf = if avail_len < Self::ENCODED_LEN {
12355 payload_buf[0..avail_len].copy_from_slice(__input);
12356 Bytes::new(&payload_buf)
12357 } else {
12358 Bytes::new(__input)
12359 };
12360 let mut __struct = Self::default();
12361 __struct.custom_mode = buf.get_u32_le();
12362 __struct.target_system = buf.get_u8();
12363 let tmp = buf.get_u8();
12364 __struct.base_mode =
12365 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
12366 enum_type: "MavMode",
12367 value: tmp as u32,
12368 })?;
12369 Ok(__struct)
12370 }
12371 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12372 let mut __tmp = BytesMut::new(bytes);
12373 #[allow(clippy::absurd_extreme_comparisons)]
12374 #[allow(unused_comparisons)]
12375 if __tmp.remaining() < Self::ENCODED_LEN {
12376 panic!(
12377 "buffer is too small (need {} bytes, but got {})",
12378 Self::ENCODED_LEN,
12379 __tmp.remaining(),
12380 )
12381 }
12382 __tmp.put_u32_le(self.custom_mode);
12383 __tmp.put_u8(self.target_system);
12384 __tmp.put_u8(self.base_mode as u8);
12385 if matches!(version, MavlinkVersion::V2) {
12386 let len = __tmp.len();
12387 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12388 } else {
12389 __tmp.len()
12390 }
12391 }
12392}
12393#[doc = "id: 50"]
12394#[doc = "Bind a RC channel to a parameter. The parameter should change according to the RC channel value."]
12395#[derive(Debug, Clone, PartialEq)]
12396#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12397#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12398pub struct PARAM_MAP_RC_DATA {
12399 #[doc = "Initial parameter value"]
12400 pub param_value0: f32,
12401 #[doc = "Scale, maps the RC range [-1, 1] to a parameter value"]
12402 pub scale: f32,
12403 #[doc = "Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation)"]
12404 pub param_value_min: f32,
12405 #[doc = "Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation)"]
12406 pub param_value_max: f32,
12407 #[doc = "Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index."]
12408 pub param_index: i16,
12409 #[doc = "System ID"]
12410 pub target_system: u8,
12411 #[doc = "Component ID"]
12412 pub target_component: u8,
12413 #[doc = "Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string"]
12414 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
12415 pub param_id: [u8; 16],
12416 #[doc = "Index of parameter RC channel. Not equal to the RC channel id. Typically corresponds to a potentiometer-knob on the RC."]
12417 pub parameter_rc_channel_index: u8,
12418}
12419impl PARAM_MAP_RC_DATA {
12420 pub const ENCODED_LEN: usize = 37usize;
12421 pub const DEFAULT: Self = Self {
12422 param_value0: 0.0_f32,
12423 scale: 0.0_f32,
12424 param_value_min: 0.0_f32,
12425 param_value_max: 0.0_f32,
12426 param_index: 0_i16,
12427 target_system: 0_u8,
12428 target_component: 0_u8,
12429 param_id: [0_u8; 16usize],
12430 parameter_rc_channel_index: 0_u8,
12431 };
12432 #[cfg(feature = "arbitrary")]
12433 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12434 use arbitrary::{Arbitrary, Unstructured};
12435 let mut buf = [0u8; 1024];
12436 rng.fill_bytes(&mut buf);
12437 let mut unstructured = Unstructured::new(&buf);
12438 Self::arbitrary(&mut unstructured).unwrap_or_default()
12439 }
12440}
12441impl Default for PARAM_MAP_RC_DATA {
12442 fn default() -> Self {
12443 Self::DEFAULT.clone()
12444 }
12445}
12446impl MessageData for PARAM_MAP_RC_DATA {
12447 type Message = MavMessage;
12448 const ID: u32 = 50u32;
12449 const NAME: &'static str = "PARAM_MAP_RC";
12450 const EXTRA_CRC: u8 = 78u8;
12451 const ENCODED_LEN: usize = 37usize;
12452 fn deser(
12453 _version: MavlinkVersion,
12454 __input: &[u8],
12455 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12456 let avail_len = __input.len();
12457 let mut payload_buf = [0; Self::ENCODED_LEN];
12458 let mut buf = if avail_len < Self::ENCODED_LEN {
12459 payload_buf[0..avail_len].copy_from_slice(__input);
12460 Bytes::new(&payload_buf)
12461 } else {
12462 Bytes::new(__input)
12463 };
12464 let mut __struct = Self::default();
12465 __struct.param_value0 = buf.get_f32_le();
12466 __struct.scale = buf.get_f32_le();
12467 __struct.param_value_min = buf.get_f32_le();
12468 __struct.param_value_max = buf.get_f32_le();
12469 __struct.param_index = buf.get_i16_le();
12470 __struct.target_system = buf.get_u8();
12471 __struct.target_component = buf.get_u8();
12472 for v in &mut __struct.param_id {
12473 let val = buf.get_u8();
12474 *v = val;
12475 }
12476 __struct.parameter_rc_channel_index = buf.get_u8();
12477 Ok(__struct)
12478 }
12479 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12480 let mut __tmp = BytesMut::new(bytes);
12481 #[allow(clippy::absurd_extreme_comparisons)]
12482 #[allow(unused_comparisons)]
12483 if __tmp.remaining() < Self::ENCODED_LEN {
12484 panic!(
12485 "buffer is too small (need {} bytes, but got {})",
12486 Self::ENCODED_LEN,
12487 __tmp.remaining(),
12488 )
12489 }
12490 __tmp.put_f32_le(self.param_value0);
12491 __tmp.put_f32_le(self.scale);
12492 __tmp.put_f32_le(self.param_value_min);
12493 __tmp.put_f32_le(self.param_value_max);
12494 __tmp.put_i16_le(self.param_index);
12495 __tmp.put_u8(self.target_system);
12496 __tmp.put_u8(self.target_component);
12497 for val in &self.param_id {
12498 __tmp.put_u8(*val);
12499 }
12500 __tmp.put_u8(self.parameter_rc_channel_index);
12501 if matches!(version, MavlinkVersion::V2) {
12502 let len = __tmp.len();
12503 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12504 } else {
12505 __tmp.len()
12506 }
12507 }
12508}
12509#[doc = "id: 320"]
12510#[doc = "Request to read the value of a parameter with either the param_id string id or param_index. PARAM_EXT_VALUE should be emitted in response."]
12511#[derive(Debug, Clone, PartialEq)]
12512#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12513#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12514pub struct PARAM_EXT_REQUEST_READ_DATA {
12515 #[doc = "Parameter index. Set to -1 to use the Parameter ID field as identifier (else param_id will be ignored)"]
12516 pub param_index: i16,
12517 #[doc = "System ID"]
12518 pub target_system: u8,
12519 #[doc = "Component ID"]
12520 pub target_component: u8,
12521 #[doc = "Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string"]
12522 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
12523 pub param_id: [u8; 16],
12524}
12525impl PARAM_EXT_REQUEST_READ_DATA {
12526 pub const ENCODED_LEN: usize = 20usize;
12527 pub const DEFAULT: Self = Self {
12528 param_index: 0_i16,
12529 target_system: 0_u8,
12530 target_component: 0_u8,
12531 param_id: [0_u8; 16usize],
12532 };
12533 #[cfg(feature = "arbitrary")]
12534 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12535 use arbitrary::{Arbitrary, Unstructured};
12536 let mut buf = [0u8; 1024];
12537 rng.fill_bytes(&mut buf);
12538 let mut unstructured = Unstructured::new(&buf);
12539 Self::arbitrary(&mut unstructured).unwrap_or_default()
12540 }
12541}
12542impl Default for PARAM_EXT_REQUEST_READ_DATA {
12543 fn default() -> Self {
12544 Self::DEFAULT.clone()
12545 }
12546}
12547impl MessageData for PARAM_EXT_REQUEST_READ_DATA {
12548 type Message = MavMessage;
12549 const ID: u32 = 320u32;
12550 const NAME: &'static str = "PARAM_EXT_REQUEST_READ";
12551 const EXTRA_CRC: u8 = 243u8;
12552 const ENCODED_LEN: usize = 20usize;
12553 fn deser(
12554 _version: MavlinkVersion,
12555 __input: &[u8],
12556 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12557 let avail_len = __input.len();
12558 let mut payload_buf = [0; Self::ENCODED_LEN];
12559 let mut buf = if avail_len < Self::ENCODED_LEN {
12560 payload_buf[0..avail_len].copy_from_slice(__input);
12561 Bytes::new(&payload_buf)
12562 } else {
12563 Bytes::new(__input)
12564 };
12565 let mut __struct = Self::default();
12566 __struct.param_index = buf.get_i16_le();
12567 __struct.target_system = buf.get_u8();
12568 __struct.target_component = buf.get_u8();
12569 for v in &mut __struct.param_id {
12570 let val = buf.get_u8();
12571 *v = val;
12572 }
12573 Ok(__struct)
12574 }
12575 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12576 let mut __tmp = BytesMut::new(bytes);
12577 #[allow(clippy::absurd_extreme_comparisons)]
12578 #[allow(unused_comparisons)]
12579 if __tmp.remaining() < Self::ENCODED_LEN {
12580 panic!(
12581 "buffer is too small (need {} bytes, but got {})",
12582 Self::ENCODED_LEN,
12583 __tmp.remaining(),
12584 )
12585 }
12586 __tmp.put_i16_le(self.param_index);
12587 __tmp.put_u8(self.target_system);
12588 __tmp.put_u8(self.target_component);
12589 for val in &self.param_id {
12590 __tmp.put_u8(*val);
12591 }
12592 if matches!(version, MavlinkVersion::V2) {
12593 let len = __tmp.len();
12594 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12595 } else {
12596 __tmp.len()
12597 }
12598 }
12599}
12600#[doc = "id: 116"]
12601#[doc = "The RAW IMU readings for secondary 9DOF sensor setup. This message should contain the scaled values to the described units."]
12602#[derive(Debug, Clone, PartialEq)]
12603#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12604#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12605pub struct SCALED_IMU2_DATA {
12606 #[doc = "Timestamp (time since system boot)."]
12607 pub time_boot_ms: u32,
12608 #[doc = "X acceleration"]
12609 pub xacc: i16,
12610 #[doc = "Y acceleration"]
12611 pub yacc: i16,
12612 #[doc = "Z acceleration"]
12613 pub zacc: i16,
12614 #[doc = "Angular speed around X axis"]
12615 pub xgyro: i16,
12616 #[doc = "Angular speed around Y axis"]
12617 pub ygyro: i16,
12618 #[doc = "Angular speed around Z axis"]
12619 pub zgyro: i16,
12620 #[doc = "X Magnetic field"]
12621 pub xmag: i16,
12622 #[doc = "Y Magnetic field"]
12623 pub ymag: i16,
12624 #[doc = "Z Magnetic field"]
12625 pub zmag: i16,
12626 #[doc = "Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C)."]
12627 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
12628 pub temperature: i16,
12629}
12630impl SCALED_IMU2_DATA {
12631 pub const ENCODED_LEN: usize = 24usize;
12632 pub const DEFAULT: Self = Self {
12633 time_boot_ms: 0_u32,
12634 xacc: 0_i16,
12635 yacc: 0_i16,
12636 zacc: 0_i16,
12637 xgyro: 0_i16,
12638 ygyro: 0_i16,
12639 zgyro: 0_i16,
12640 xmag: 0_i16,
12641 ymag: 0_i16,
12642 zmag: 0_i16,
12643 temperature: 0_i16,
12644 };
12645 #[cfg(feature = "arbitrary")]
12646 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12647 use arbitrary::{Arbitrary, Unstructured};
12648 let mut buf = [0u8; 1024];
12649 rng.fill_bytes(&mut buf);
12650 let mut unstructured = Unstructured::new(&buf);
12651 Self::arbitrary(&mut unstructured).unwrap_or_default()
12652 }
12653}
12654impl Default for SCALED_IMU2_DATA {
12655 fn default() -> Self {
12656 Self::DEFAULT.clone()
12657 }
12658}
12659impl MessageData for SCALED_IMU2_DATA {
12660 type Message = MavMessage;
12661 const ID: u32 = 116u32;
12662 const NAME: &'static str = "SCALED_IMU2";
12663 const EXTRA_CRC: u8 = 76u8;
12664 const ENCODED_LEN: usize = 24usize;
12665 fn deser(
12666 _version: MavlinkVersion,
12667 __input: &[u8],
12668 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12669 let avail_len = __input.len();
12670 let mut payload_buf = [0; Self::ENCODED_LEN];
12671 let mut buf = if avail_len < Self::ENCODED_LEN {
12672 payload_buf[0..avail_len].copy_from_slice(__input);
12673 Bytes::new(&payload_buf)
12674 } else {
12675 Bytes::new(__input)
12676 };
12677 let mut __struct = Self::default();
12678 __struct.time_boot_ms = buf.get_u32_le();
12679 __struct.xacc = buf.get_i16_le();
12680 __struct.yacc = buf.get_i16_le();
12681 __struct.zacc = buf.get_i16_le();
12682 __struct.xgyro = buf.get_i16_le();
12683 __struct.ygyro = buf.get_i16_le();
12684 __struct.zgyro = buf.get_i16_le();
12685 __struct.xmag = buf.get_i16_le();
12686 __struct.ymag = buf.get_i16_le();
12687 __struct.zmag = buf.get_i16_le();
12688 __struct.temperature = buf.get_i16_le();
12689 Ok(__struct)
12690 }
12691 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12692 let mut __tmp = BytesMut::new(bytes);
12693 #[allow(clippy::absurd_extreme_comparisons)]
12694 #[allow(unused_comparisons)]
12695 if __tmp.remaining() < Self::ENCODED_LEN {
12696 panic!(
12697 "buffer is too small (need {} bytes, but got {})",
12698 Self::ENCODED_LEN,
12699 __tmp.remaining(),
12700 )
12701 }
12702 __tmp.put_u32_le(self.time_boot_ms);
12703 __tmp.put_i16_le(self.xacc);
12704 __tmp.put_i16_le(self.yacc);
12705 __tmp.put_i16_le(self.zacc);
12706 __tmp.put_i16_le(self.xgyro);
12707 __tmp.put_i16_le(self.ygyro);
12708 __tmp.put_i16_le(self.zgyro);
12709 __tmp.put_i16_le(self.xmag);
12710 __tmp.put_i16_le(self.ymag);
12711 __tmp.put_i16_le(self.zmag);
12712 __tmp.put_i16_le(self.temperature);
12713 if matches!(version, MavlinkVersion::V2) {
12714 let len = __tmp.len();
12715 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12716 } else {
12717 __tmp.len()
12718 }
12719 }
12720}
12721#[doc = "id: 258"]
12722#[doc = "Control vehicle tone generation (buzzer)."]
12723#[derive(Debug, Clone, PartialEq)]
12724#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12725#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12726pub struct PLAY_TUNE_DATA {
12727 #[doc = "System ID"]
12728 pub target_system: u8,
12729 #[doc = "Component ID"]
12730 pub target_component: u8,
12731 #[doc = "tune in board specific format"]
12732 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
12733 pub tune: [u8; 30],
12734 #[doc = "tune extension (appended to tune)"]
12735 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
12736 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
12737 pub tune2: [u8; 200],
12738}
12739impl PLAY_TUNE_DATA {
12740 pub const ENCODED_LEN: usize = 232usize;
12741 pub const DEFAULT: Self = Self {
12742 target_system: 0_u8,
12743 target_component: 0_u8,
12744 tune: [0_u8; 30usize],
12745 tune2: [0_u8; 200usize],
12746 };
12747 #[cfg(feature = "arbitrary")]
12748 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12749 use arbitrary::{Arbitrary, Unstructured};
12750 let mut buf = [0u8; 1024];
12751 rng.fill_bytes(&mut buf);
12752 let mut unstructured = Unstructured::new(&buf);
12753 Self::arbitrary(&mut unstructured).unwrap_or_default()
12754 }
12755}
12756impl Default for PLAY_TUNE_DATA {
12757 fn default() -> Self {
12758 Self::DEFAULT.clone()
12759 }
12760}
12761impl MessageData for PLAY_TUNE_DATA {
12762 type Message = MavMessage;
12763 const ID: u32 = 258u32;
12764 const NAME: &'static str = "PLAY_TUNE";
12765 const EXTRA_CRC: u8 = 187u8;
12766 const ENCODED_LEN: usize = 232usize;
12767 fn deser(
12768 _version: MavlinkVersion,
12769 __input: &[u8],
12770 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12771 let avail_len = __input.len();
12772 let mut payload_buf = [0; Self::ENCODED_LEN];
12773 let mut buf = if avail_len < Self::ENCODED_LEN {
12774 payload_buf[0..avail_len].copy_from_slice(__input);
12775 Bytes::new(&payload_buf)
12776 } else {
12777 Bytes::new(__input)
12778 };
12779 let mut __struct = Self::default();
12780 __struct.target_system = buf.get_u8();
12781 __struct.target_component = buf.get_u8();
12782 for v in &mut __struct.tune {
12783 let val = buf.get_u8();
12784 *v = val;
12785 }
12786 for v in &mut __struct.tune2 {
12787 let val = buf.get_u8();
12788 *v = val;
12789 }
12790 Ok(__struct)
12791 }
12792 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12793 let mut __tmp = BytesMut::new(bytes);
12794 #[allow(clippy::absurd_extreme_comparisons)]
12795 #[allow(unused_comparisons)]
12796 if __tmp.remaining() < Self::ENCODED_LEN {
12797 panic!(
12798 "buffer is too small (need {} bytes, but got {})",
12799 Self::ENCODED_LEN,
12800 __tmp.remaining(),
12801 )
12802 }
12803 __tmp.put_u8(self.target_system);
12804 __tmp.put_u8(self.target_component);
12805 for val in &self.tune {
12806 __tmp.put_u8(*val);
12807 }
12808 for val in &self.tune2 {
12809 __tmp.put_u8(*val);
12810 }
12811 if matches!(version, MavlinkVersion::V2) {
12812 let len = __tmp.len();
12813 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12814 } else {
12815 __tmp.len()
12816 }
12817 }
12818}
12819#[doc = "id: 21"]
12820#[doc = "Request all parameters of this component. After this request, all parameters are emitted. The parameter microservice is documented at <https://mavlink.io/en/services/parameter.html>."]
12821#[derive(Debug, Clone, PartialEq)]
12822#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12823#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12824pub struct PARAM_REQUEST_LIST_DATA {
12825 #[doc = "System ID"]
12826 pub target_system: u8,
12827 #[doc = "Component ID"]
12828 pub target_component: u8,
12829}
12830impl PARAM_REQUEST_LIST_DATA {
12831 pub const ENCODED_LEN: usize = 2usize;
12832 pub const DEFAULT: Self = Self {
12833 target_system: 0_u8,
12834 target_component: 0_u8,
12835 };
12836 #[cfg(feature = "arbitrary")]
12837 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12838 use arbitrary::{Arbitrary, Unstructured};
12839 let mut buf = [0u8; 1024];
12840 rng.fill_bytes(&mut buf);
12841 let mut unstructured = Unstructured::new(&buf);
12842 Self::arbitrary(&mut unstructured).unwrap_or_default()
12843 }
12844}
12845impl Default for PARAM_REQUEST_LIST_DATA {
12846 fn default() -> Self {
12847 Self::DEFAULT.clone()
12848 }
12849}
12850impl MessageData for PARAM_REQUEST_LIST_DATA {
12851 type Message = MavMessage;
12852 const ID: u32 = 21u32;
12853 const NAME: &'static str = "PARAM_REQUEST_LIST";
12854 const EXTRA_CRC: u8 = 159u8;
12855 const ENCODED_LEN: usize = 2usize;
12856 fn deser(
12857 _version: MavlinkVersion,
12858 __input: &[u8],
12859 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12860 let avail_len = __input.len();
12861 let mut payload_buf = [0; Self::ENCODED_LEN];
12862 let mut buf = if avail_len < Self::ENCODED_LEN {
12863 payload_buf[0..avail_len].copy_from_slice(__input);
12864 Bytes::new(&payload_buf)
12865 } else {
12866 Bytes::new(__input)
12867 };
12868 let mut __struct = Self::default();
12869 __struct.target_system = buf.get_u8();
12870 __struct.target_component = buf.get_u8();
12871 Ok(__struct)
12872 }
12873 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12874 let mut __tmp = BytesMut::new(bytes);
12875 #[allow(clippy::absurd_extreme_comparisons)]
12876 #[allow(unused_comparisons)]
12877 if __tmp.remaining() < Self::ENCODED_LEN {
12878 panic!(
12879 "buffer is too small (need {} bytes, but got {})",
12880 Self::ENCODED_LEN,
12881 __tmp.remaining(),
12882 )
12883 }
12884 __tmp.put_u8(self.target_system);
12885 __tmp.put_u8(self.target_component);
12886 if matches!(version, MavlinkVersion::V2) {
12887 let len = __tmp.len();
12888 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12889 } else {
12890 __tmp.len()
12891 }
12892 }
12893}
12894#[doc = "id: 7"]
12895#[doc = "Emit an encrypted signature / key identifying this system. PLEASE NOTE: This protocol has been kept simple, so transmitting the key requires an encrypted channel for true safety."]
12896#[derive(Debug, Clone, PartialEq)]
12897#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12898#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12899pub struct AUTH_KEY_DATA {
12900 #[doc = "key"]
12901 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
12902 pub key: [u8; 32],
12903}
12904impl AUTH_KEY_DATA {
12905 pub const ENCODED_LEN: usize = 32usize;
12906 pub const DEFAULT: Self = Self {
12907 key: [0_u8; 32usize],
12908 };
12909 #[cfg(feature = "arbitrary")]
12910 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12911 use arbitrary::{Arbitrary, Unstructured};
12912 let mut buf = [0u8; 1024];
12913 rng.fill_bytes(&mut buf);
12914 let mut unstructured = Unstructured::new(&buf);
12915 Self::arbitrary(&mut unstructured).unwrap_or_default()
12916 }
12917}
12918impl Default for AUTH_KEY_DATA {
12919 fn default() -> Self {
12920 Self::DEFAULT.clone()
12921 }
12922}
12923impl MessageData for AUTH_KEY_DATA {
12924 type Message = MavMessage;
12925 const ID: u32 = 7u32;
12926 const NAME: &'static str = "AUTH_KEY";
12927 const EXTRA_CRC: u8 = 119u8;
12928 const ENCODED_LEN: usize = 32usize;
12929 fn deser(
12930 _version: MavlinkVersion,
12931 __input: &[u8],
12932 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12933 let avail_len = __input.len();
12934 let mut payload_buf = [0; Self::ENCODED_LEN];
12935 let mut buf = if avail_len < Self::ENCODED_LEN {
12936 payload_buf[0..avail_len].copy_from_slice(__input);
12937 Bytes::new(&payload_buf)
12938 } else {
12939 Bytes::new(__input)
12940 };
12941 let mut __struct = Self::default();
12942 for v in &mut __struct.key {
12943 let val = buf.get_u8();
12944 *v = val;
12945 }
12946 Ok(__struct)
12947 }
12948 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12949 let mut __tmp = BytesMut::new(bytes);
12950 #[allow(clippy::absurd_extreme_comparisons)]
12951 #[allow(unused_comparisons)]
12952 if __tmp.remaining() < Self::ENCODED_LEN {
12953 panic!(
12954 "buffer is too small (need {} bytes, but got {})",
12955 Self::ENCODED_LEN,
12956 __tmp.remaining(),
12957 )
12958 }
12959 for val in &self.key {
12960 __tmp.put_u8(*val);
12961 }
12962 if matches!(version, MavlinkVersion::V2) {
12963 let len = __tmp.len();
12964 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12965 } else {
12966 __tmp.len()
12967 }
12968 }
12969}
12970#[doc = "id: 80"]
12971#[doc = "Cancel a long running command. The target system should respond with a COMMAND_ACK to the original command with result=MAV_RESULT_CANCELLED if the long running process was cancelled. If it has already completed, the cancel action can be ignored. The cancel action can be retried until some sort of acknowledgement to the original command has been received. The command microservice is documented at <https://mavlink.io/en/services/command.html>."]
12972#[derive(Debug, Clone, PartialEq)]
12973#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12974#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12975pub struct COMMAND_CANCEL_DATA {
12976 #[doc = "Command ID (of command to cancel)."]
12977 pub command: MavCmd,
12978 #[doc = "System executing long running command. Should not be broadcast (0)."]
12979 pub target_system: u8,
12980 #[doc = "Component executing long running command."]
12981 pub target_component: u8,
12982}
12983impl COMMAND_CANCEL_DATA {
12984 pub const ENCODED_LEN: usize = 4usize;
12985 pub const DEFAULT: Self = Self {
12986 command: MavCmd::DEFAULT,
12987 target_system: 0_u8,
12988 target_component: 0_u8,
12989 };
12990 #[cfg(feature = "arbitrary")]
12991 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12992 use arbitrary::{Arbitrary, Unstructured};
12993 let mut buf = [0u8; 1024];
12994 rng.fill_bytes(&mut buf);
12995 let mut unstructured = Unstructured::new(&buf);
12996 Self::arbitrary(&mut unstructured).unwrap_or_default()
12997 }
12998}
12999impl Default for COMMAND_CANCEL_DATA {
13000 fn default() -> Self {
13001 Self::DEFAULT.clone()
13002 }
13003}
13004impl MessageData for COMMAND_CANCEL_DATA {
13005 type Message = MavMessage;
13006 const ID: u32 = 80u32;
13007 const NAME: &'static str = "COMMAND_CANCEL";
13008 const EXTRA_CRC: u8 = 14u8;
13009 const ENCODED_LEN: usize = 4usize;
13010 fn deser(
13011 _version: MavlinkVersion,
13012 __input: &[u8],
13013 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13014 let avail_len = __input.len();
13015 let mut payload_buf = [0; Self::ENCODED_LEN];
13016 let mut buf = if avail_len < Self::ENCODED_LEN {
13017 payload_buf[0..avail_len].copy_from_slice(__input);
13018 Bytes::new(&payload_buf)
13019 } else {
13020 Bytes::new(__input)
13021 };
13022 let mut __struct = Self::default();
13023 let tmp = buf.get_u16_le();
13024 __struct.command = FromPrimitive::from_u16(tmp).ok_or(
13025 ::mavlink_core::error::ParserError::InvalidEnum {
13026 enum_type: "MavCmd",
13027 value: tmp as u32,
13028 },
13029 )?;
13030 __struct.target_system = buf.get_u8();
13031 __struct.target_component = buf.get_u8();
13032 Ok(__struct)
13033 }
13034 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13035 let mut __tmp = BytesMut::new(bytes);
13036 #[allow(clippy::absurd_extreme_comparisons)]
13037 #[allow(unused_comparisons)]
13038 if __tmp.remaining() < Self::ENCODED_LEN {
13039 panic!(
13040 "buffer is too small (need {} bytes, but got {})",
13041 Self::ENCODED_LEN,
13042 __tmp.remaining(),
13043 )
13044 }
13045 __tmp.put_u16_le(self.command as u16);
13046 __tmp.put_u8(self.target_system);
13047 __tmp.put_u8(self.target_component);
13048 if matches!(version, MavlinkVersion::V2) {
13049 let len = __tmp.len();
13050 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13051 } else {
13052 __tmp.len()
13053 }
13054 }
13055}
13056#[doc = "id: 69"]
13057#[doc = "This message provides an API for manually controlling the vehicle using standard joystick axes nomenclature, along with a joystick-like input device. Unused axes can be disabled and buttons states are transmitted as individual on/off bits of a bitmask."]
13058#[derive(Debug, Clone, PartialEq)]
13059#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13060#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13061pub struct MANUAL_CONTROL_DATA {
13062 #[doc = "X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle."]
13063 pub x: i16,
13064 #[doc = "Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle."]
13065 pub y: i16,
13066 #[doc = "Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust."]
13067 pub z: i16,
13068 #[doc = "R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle."]
13069 pub r: i16,
13070 #[doc = "A bitfield corresponding to the joystick buttons' 0-15 current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1."]
13071 pub buttons: u16,
13072 #[doc = "The system to be controlled."]
13073 pub target: u8,
13074 #[doc = "A bitfield corresponding to the joystick buttons' 16-31 current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 16."]
13075 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
13076 pub buttons2: u16,
13077 #[doc = "Set bits to 1 to indicate which of the following extension fields contain valid data: bit 0: pitch, bit 1: roll, bit 2: aux1, bit 3: aux2, bit 4: aux3, bit 5: aux4, bit 6: aux5, bit 7: aux6"]
13078 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
13079 pub enabled_extensions: u8,
13080 #[doc = "Pitch-only-axis, normalized to the range [-1000,1000]. Generally corresponds to pitch on vehicles with additional degrees of freedom. Valid if bit 0 of enabled_extensions field is set. Set to 0 if invalid."]
13081 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
13082 pub s: i16,
13083 #[doc = "Roll-only-axis, normalized to the range [-1000,1000]. Generally corresponds to roll on vehicles with additional degrees of freedom. Valid if bit 1 of enabled_extensions field is set. Set to 0 if invalid."]
13084 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
13085 pub t: i16,
13086 #[doc = "Aux continuous input field 1. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 2 of enabled_extensions field is set. 0 if bit 2 is unset."]
13087 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
13088 pub aux1: i16,
13089 #[doc = "Aux continuous input field 2. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 3 of enabled_extensions field is set. 0 if bit 3 is unset."]
13090 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
13091 pub aux2: i16,
13092 #[doc = "Aux continuous input field 3. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 4 of enabled_extensions field is set. 0 if bit 4 is unset."]
13093 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
13094 pub aux3: i16,
13095 #[doc = "Aux continuous input field 4. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 5 of enabled_extensions field is set. 0 if bit 5 is unset."]
13096 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
13097 pub aux4: i16,
13098 #[doc = "Aux continuous input field 5. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 6 of enabled_extensions field is set. 0 if bit 6 is unset."]
13099 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
13100 pub aux5: i16,
13101 #[doc = "Aux continuous input field 6. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 7 of enabled_extensions field is set. 0 if bit 7 is unset."]
13102 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
13103 pub aux6: i16,
13104}
13105impl MANUAL_CONTROL_DATA {
13106 pub const ENCODED_LEN: usize = 30usize;
13107 pub const DEFAULT: Self = Self {
13108 x: 0_i16,
13109 y: 0_i16,
13110 z: 0_i16,
13111 r: 0_i16,
13112 buttons: 0_u16,
13113 target: 0_u8,
13114 buttons2: 0_u16,
13115 enabled_extensions: 0_u8,
13116 s: 0_i16,
13117 t: 0_i16,
13118 aux1: 0_i16,
13119 aux2: 0_i16,
13120 aux3: 0_i16,
13121 aux4: 0_i16,
13122 aux5: 0_i16,
13123 aux6: 0_i16,
13124 };
13125 #[cfg(feature = "arbitrary")]
13126 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13127 use arbitrary::{Arbitrary, Unstructured};
13128 let mut buf = [0u8; 1024];
13129 rng.fill_bytes(&mut buf);
13130 let mut unstructured = Unstructured::new(&buf);
13131 Self::arbitrary(&mut unstructured).unwrap_or_default()
13132 }
13133}
13134impl Default for MANUAL_CONTROL_DATA {
13135 fn default() -> Self {
13136 Self::DEFAULT.clone()
13137 }
13138}
13139impl MessageData for MANUAL_CONTROL_DATA {
13140 type Message = MavMessage;
13141 const ID: u32 = 69u32;
13142 const NAME: &'static str = "MANUAL_CONTROL";
13143 const EXTRA_CRC: u8 = 243u8;
13144 const ENCODED_LEN: usize = 30usize;
13145 fn deser(
13146 _version: MavlinkVersion,
13147 __input: &[u8],
13148 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13149 let avail_len = __input.len();
13150 let mut payload_buf = [0; Self::ENCODED_LEN];
13151 let mut buf = if avail_len < Self::ENCODED_LEN {
13152 payload_buf[0..avail_len].copy_from_slice(__input);
13153 Bytes::new(&payload_buf)
13154 } else {
13155 Bytes::new(__input)
13156 };
13157 let mut __struct = Self::default();
13158 __struct.x = buf.get_i16_le();
13159 __struct.y = buf.get_i16_le();
13160 __struct.z = buf.get_i16_le();
13161 __struct.r = buf.get_i16_le();
13162 __struct.buttons = buf.get_u16_le();
13163 __struct.target = buf.get_u8();
13164 __struct.buttons2 = buf.get_u16_le();
13165 __struct.enabled_extensions = buf.get_u8();
13166 __struct.s = buf.get_i16_le();
13167 __struct.t = buf.get_i16_le();
13168 __struct.aux1 = buf.get_i16_le();
13169 __struct.aux2 = buf.get_i16_le();
13170 __struct.aux3 = buf.get_i16_le();
13171 __struct.aux4 = buf.get_i16_le();
13172 __struct.aux5 = buf.get_i16_le();
13173 __struct.aux6 = buf.get_i16_le();
13174 Ok(__struct)
13175 }
13176 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13177 let mut __tmp = BytesMut::new(bytes);
13178 #[allow(clippy::absurd_extreme_comparisons)]
13179 #[allow(unused_comparisons)]
13180 if __tmp.remaining() < Self::ENCODED_LEN {
13181 panic!(
13182 "buffer is too small (need {} bytes, but got {})",
13183 Self::ENCODED_LEN,
13184 __tmp.remaining(),
13185 )
13186 }
13187 __tmp.put_i16_le(self.x);
13188 __tmp.put_i16_le(self.y);
13189 __tmp.put_i16_le(self.z);
13190 __tmp.put_i16_le(self.r);
13191 __tmp.put_u16_le(self.buttons);
13192 __tmp.put_u8(self.target);
13193 __tmp.put_u16_le(self.buttons2);
13194 __tmp.put_u8(self.enabled_extensions);
13195 __tmp.put_i16_le(self.s);
13196 __tmp.put_i16_le(self.t);
13197 __tmp.put_i16_le(self.aux1);
13198 __tmp.put_i16_le(self.aux2);
13199 __tmp.put_i16_le(self.aux3);
13200 __tmp.put_i16_le(self.aux4);
13201 __tmp.put_i16_le(self.aux5);
13202 __tmp.put_i16_le(self.aux6);
13203 if matches!(version, MavlinkVersion::V2) {
13204 let len = __tmp.len();
13205 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13206 } else {
13207 __tmp.len()
13208 }
13209 }
13210}
13211#[doc = "id: 75"]
13212#[doc = "Send a command with up to seven parameters to the MAV, where params 5 and 6 are integers and the other values are floats. This is preferred over COMMAND_LONG as it allows the MAV_FRAME to be specified for interpreting positional information, such as altitude. COMMAND_INT is also preferred when sending latitude and longitude data in params 5 and 6, as it allows for greater precision. Param 5 and 6 encode positional data as scaled integers, where the scaling depends on the actual command value. NaN or INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component's current latitude, yaw rather than a specific value). The command microservice is documented at <https://mavlink.io/en/services/command.html>."]
13213#[derive(Debug, Clone, PartialEq)]
13214#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13215#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13216pub struct COMMAND_INT_DATA {
13217 #[doc = "PARAM1, see MAV_CMD enum"]
13218 pub param1: f32,
13219 #[doc = "PARAM2, see MAV_CMD enum"]
13220 pub param2: f32,
13221 #[doc = "PARAM3, see MAV_CMD enum"]
13222 pub param3: f32,
13223 #[doc = "PARAM4, see MAV_CMD enum"]
13224 pub param4: f32,
13225 #[doc = "PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7"]
13226 pub x: i32,
13227 #[doc = "PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7"]
13228 pub y: i32,
13229 #[doc = "PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame)."]
13230 pub z: f32,
13231 #[doc = "The scheduled action for the mission item."]
13232 pub command: MavCmd,
13233 #[doc = "System ID"]
13234 pub target_system: u8,
13235 #[doc = "Component ID"]
13236 pub target_component: u8,
13237 #[doc = "The coordinate system of the COMMAND."]
13238 pub frame: MavFrame,
13239 #[doc = "Not used."]
13240 pub current: u8,
13241 #[doc = "Not used (set 0)."]
13242 pub autocontinue: u8,
13243}
13244impl COMMAND_INT_DATA {
13245 pub const ENCODED_LEN: usize = 35usize;
13246 pub const DEFAULT: Self = Self {
13247 param1: 0.0_f32,
13248 param2: 0.0_f32,
13249 param3: 0.0_f32,
13250 param4: 0.0_f32,
13251 x: 0_i32,
13252 y: 0_i32,
13253 z: 0.0_f32,
13254 command: MavCmd::DEFAULT,
13255 target_system: 0_u8,
13256 target_component: 0_u8,
13257 frame: MavFrame::DEFAULT,
13258 current: 0_u8,
13259 autocontinue: 0_u8,
13260 };
13261 #[cfg(feature = "arbitrary")]
13262 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13263 use arbitrary::{Arbitrary, Unstructured};
13264 let mut buf = [0u8; 1024];
13265 rng.fill_bytes(&mut buf);
13266 let mut unstructured = Unstructured::new(&buf);
13267 Self::arbitrary(&mut unstructured).unwrap_or_default()
13268 }
13269}
13270impl Default for COMMAND_INT_DATA {
13271 fn default() -> Self {
13272 Self::DEFAULT.clone()
13273 }
13274}
13275impl MessageData for COMMAND_INT_DATA {
13276 type Message = MavMessage;
13277 const ID: u32 = 75u32;
13278 const NAME: &'static str = "COMMAND_INT";
13279 const EXTRA_CRC: u8 = 158u8;
13280 const ENCODED_LEN: usize = 35usize;
13281 fn deser(
13282 _version: MavlinkVersion,
13283 __input: &[u8],
13284 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13285 let avail_len = __input.len();
13286 let mut payload_buf = [0; Self::ENCODED_LEN];
13287 let mut buf = if avail_len < Self::ENCODED_LEN {
13288 payload_buf[0..avail_len].copy_from_slice(__input);
13289 Bytes::new(&payload_buf)
13290 } else {
13291 Bytes::new(__input)
13292 };
13293 let mut __struct = Self::default();
13294 __struct.param1 = buf.get_f32_le();
13295 __struct.param2 = buf.get_f32_le();
13296 __struct.param3 = buf.get_f32_le();
13297 __struct.param4 = buf.get_f32_le();
13298 __struct.x = buf.get_i32_le();
13299 __struct.y = buf.get_i32_le();
13300 __struct.z = buf.get_f32_le();
13301 let tmp = buf.get_u16_le();
13302 __struct.command = FromPrimitive::from_u16(tmp).ok_or(
13303 ::mavlink_core::error::ParserError::InvalidEnum {
13304 enum_type: "MavCmd",
13305 value: tmp as u32,
13306 },
13307 )?;
13308 __struct.target_system = buf.get_u8();
13309 __struct.target_component = buf.get_u8();
13310 let tmp = buf.get_u8();
13311 __struct.frame =
13312 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
13313 enum_type: "MavFrame",
13314 value: tmp as u32,
13315 })?;
13316 __struct.current = buf.get_u8();
13317 __struct.autocontinue = buf.get_u8();
13318 Ok(__struct)
13319 }
13320 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13321 let mut __tmp = BytesMut::new(bytes);
13322 #[allow(clippy::absurd_extreme_comparisons)]
13323 #[allow(unused_comparisons)]
13324 if __tmp.remaining() < Self::ENCODED_LEN {
13325 panic!(
13326 "buffer is too small (need {} bytes, but got {})",
13327 Self::ENCODED_LEN,
13328 __tmp.remaining(),
13329 )
13330 }
13331 __tmp.put_f32_le(self.param1);
13332 __tmp.put_f32_le(self.param2);
13333 __tmp.put_f32_le(self.param3);
13334 __tmp.put_f32_le(self.param4);
13335 __tmp.put_i32_le(self.x);
13336 __tmp.put_i32_le(self.y);
13337 __tmp.put_f32_le(self.z);
13338 __tmp.put_u16_le(self.command as u16);
13339 __tmp.put_u8(self.target_system);
13340 __tmp.put_u8(self.target_component);
13341 __tmp.put_u8(self.frame as u8);
13342 __tmp.put_u8(self.current);
13343 __tmp.put_u8(self.autocontinue);
13344 if matches!(version, MavlinkVersion::V2) {
13345 let len = __tmp.len();
13346 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13347 } else {
13348 __tmp.len()
13349 }
13350 }
13351}
13352#[doc = "id: 91"]
13353#[doc = "Sent from autopilot to simulation. Hardware in the loop control outputs. Alternative to HIL_ACTUATOR_CONTROLS."]
13354#[derive(Debug, Clone, PartialEq)]
13355#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13356#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13357pub struct HIL_CONTROLS_DATA {
13358 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
13359 pub time_usec: u64,
13360 #[doc = "Control output -1 .. 1"]
13361 pub roll_ailerons: f32,
13362 #[doc = "Control output -1 .. 1"]
13363 pub pitch_elevator: f32,
13364 #[doc = "Control output -1 .. 1"]
13365 pub yaw_rudder: f32,
13366 #[doc = "Throttle 0 .. 1"]
13367 pub throttle: f32,
13368 #[doc = "Aux 1, -1 .. 1"]
13369 pub aux1: f32,
13370 #[doc = "Aux 2, -1 .. 1"]
13371 pub aux2: f32,
13372 #[doc = "Aux 3, -1 .. 1"]
13373 pub aux3: f32,
13374 #[doc = "Aux 4, -1 .. 1"]
13375 pub aux4: f32,
13376 #[doc = "System mode."]
13377 pub mode: MavMode,
13378 #[doc = "Navigation mode (MAV_NAV_MODE)"]
13379 pub nav_mode: u8,
13380}
13381impl HIL_CONTROLS_DATA {
13382 pub const ENCODED_LEN: usize = 42usize;
13383 pub const DEFAULT: Self = Self {
13384 time_usec: 0_u64,
13385 roll_ailerons: 0.0_f32,
13386 pitch_elevator: 0.0_f32,
13387 yaw_rudder: 0.0_f32,
13388 throttle: 0.0_f32,
13389 aux1: 0.0_f32,
13390 aux2: 0.0_f32,
13391 aux3: 0.0_f32,
13392 aux4: 0.0_f32,
13393 mode: MavMode::DEFAULT,
13394 nav_mode: 0_u8,
13395 };
13396 #[cfg(feature = "arbitrary")]
13397 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13398 use arbitrary::{Arbitrary, Unstructured};
13399 let mut buf = [0u8; 1024];
13400 rng.fill_bytes(&mut buf);
13401 let mut unstructured = Unstructured::new(&buf);
13402 Self::arbitrary(&mut unstructured).unwrap_or_default()
13403 }
13404}
13405impl Default for HIL_CONTROLS_DATA {
13406 fn default() -> Self {
13407 Self::DEFAULT.clone()
13408 }
13409}
13410impl MessageData for HIL_CONTROLS_DATA {
13411 type Message = MavMessage;
13412 const ID: u32 = 91u32;
13413 const NAME: &'static str = "HIL_CONTROLS";
13414 const EXTRA_CRC: u8 = 63u8;
13415 const ENCODED_LEN: usize = 42usize;
13416 fn deser(
13417 _version: MavlinkVersion,
13418 __input: &[u8],
13419 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13420 let avail_len = __input.len();
13421 let mut payload_buf = [0; Self::ENCODED_LEN];
13422 let mut buf = if avail_len < Self::ENCODED_LEN {
13423 payload_buf[0..avail_len].copy_from_slice(__input);
13424 Bytes::new(&payload_buf)
13425 } else {
13426 Bytes::new(__input)
13427 };
13428 let mut __struct = Self::default();
13429 __struct.time_usec = buf.get_u64_le();
13430 __struct.roll_ailerons = buf.get_f32_le();
13431 __struct.pitch_elevator = buf.get_f32_le();
13432 __struct.yaw_rudder = buf.get_f32_le();
13433 __struct.throttle = buf.get_f32_le();
13434 __struct.aux1 = buf.get_f32_le();
13435 __struct.aux2 = buf.get_f32_le();
13436 __struct.aux3 = buf.get_f32_le();
13437 __struct.aux4 = buf.get_f32_le();
13438 let tmp = buf.get_u8();
13439 __struct.mode =
13440 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
13441 enum_type: "MavMode",
13442 value: tmp as u32,
13443 })?;
13444 __struct.nav_mode = buf.get_u8();
13445 Ok(__struct)
13446 }
13447 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13448 let mut __tmp = BytesMut::new(bytes);
13449 #[allow(clippy::absurd_extreme_comparisons)]
13450 #[allow(unused_comparisons)]
13451 if __tmp.remaining() < Self::ENCODED_LEN {
13452 panic!(
13453 "buffer is too small (need {} bytes, but got {})",
13454 Self::ENCODED_LEN,
13455 __tmp.remaining(),
13456 )
13457 }
13458 __tmp.put_u64_le(self.time_usec);
13459 __tmp.put_f32_le(self.roll_ailerons);
13460 __tmp.put_f32_le(self.pitch_elevator);
13461 __tmp.put_f32_le(self.yaw_rudder);
13462 __tmp.put_f32_le(self.throttle);
13463 __tmp.put_f32_le(self.aux1);
13464 __tmp.put_f32_le(self.aux2);
13465 __tmp.put_f32_le(self.aux3);
13466 __tmp.put_f32_le(self.aux4);
13467 __tmp.put_u8(self.mode as u8);
13468 __tmp.put_u8(self.nav_mode);
13469 if matches!(version, MavlinkVersion::V2) {
13470 let len = __tmp.len();
13471 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13472 } else {
13473 __tmp.len()
13474 }
13475 }
13476}
13477#[doc = "id: 102"]
13478#[doc = "Local position/attitude estimate from a vision source."]
13479#[derive(Debug, Clone, PartialEq)]
13480#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13481#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13482pub struct VISION_POSITION_ESTIMATE_DATA {
13483 #[doc = "Timestamp (UNIX time or time since system boot)"]
13484 pub usec: u64,
13485 #[doc = "Local X position"]
13486 pub x: f32,
13487 #[doc = "Local Y position"]
13488 pub y: f32,
13489 #[doc = "Local Z position"]
13490 pub z: f32,
13491 #[doc = "Roll angle"]
13492 pub roll: f32,
13493 #[doc = "Pitch angle"]
13494 pub pitch: f32,
13495 #[doc = "Yaw angle"]
13496 pub yaw: f32,
13497 #[doc = "Row-major representation of pose 6x6 cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array."]
13498 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
13499 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
13500 pub covariance: [f32; 21],
13501 #[doc = "Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps."]
13502 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
13503 pub reset_counter: u8,
13504}
13505impl VISION_POSITION_ESTIMATE_DATA {
13506 pub const ENCODED_LEN: usize = 117usize;
13507 pub const DEFAULT: Self = Self {
13508 usec: 0_u64,
13509 x: 0.0_f32,
13510 y: 0.0_f32,
13511 z: 0.0_f32,
13512 roll: 0.0_f32,
13513 pitch: 0.0_f32,
13514 yaw: 0.0_f32,
13515 covariance: [0.0_f32; 21usize],
13516 reset_counter: 0_u8,
13517 };
13518 #[cfg(feature = "arbitrary")]
13519 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13520 use arbitrary::{Arbitrary, Unstructured};
13521 let mut buf = [0u8; 1024];
13522 rng.fill_bytes(&mut buf);
13523 let mut unstructured = Unstructured::new(&buf);
13524 Self::arbitrary(&mut unstructured).unwrap_or_default()
13525 }
13526}
13527impl Default for VISION_POSITION_ESTIMATE_DATA {
13528 fn default() -> Self {
13529 Self::DEFAULT.clone()
13530 }
13531}
13532impl MessageData for VISION_POSITION_ESTIMATE_DATA {
13533 type Message = MavMessage;
13534 const ID: u32 = 102u32;
13535 const NAME: &'static str = "VISION_POSITION_ESTIMATE";
13536 const EXTRA_CRC: u8 = 158u8;
13537 const ENCODED_LEN: usize = 117usize;
13538 fn deser(
13539 _version: MavlinkVersion,
13540 __input: &[u8],
13541 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13542 let avail_len = __input.len();
13543 let mut payload_buf = [0; Self::ENCODED_LEN];
13544 let mut buf = if avail_len < Self::ENCODED_LEN {
13545 payload_buf[0..avail_len].copy_from_slice(__input);
13546 Bytes::new(&payload_buf)
13547 } else {
13548 Bytes::new(__input)
13549 };
13550 let mut __struct = Self::default();
13551 __struct.usec = buf.get_u64_le();
13552 __struct.x = buf.get_f32_le();
13553 __struct.y = buf.get_f32_le();
13554 __struct.z = buf.get_f32_le();
13555 __struct.roll = buf.get_f32_le();
13556 __struct.pitch = buf.get_f32_le();
13557 __struct.yaw = buf.get_f32_le();
13558 for v in &mut __struct.covariance {
13559 let val = buf.get_f32_le();
13560 *v = val;
13561 }
13562 __struct.reset_counter = buf.get_u8();
13563 Ok(__struct)
13564 }
13565 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13566 let mut __tmp = BytesMut::new(bytes);
13567 #[allow(clippy::absurd_extreme_comparisons)]
13568 #[allow(unused_comparisons)]
13569 if __tmp.remaining() < Self::ENCODED_LEN {
13570 panic!(
13571 "buffer is too small (need {} bytes, but got {})",
13572 Self::ENCODED_LEN,
13573 __tmp.remaining(),
13574 )
13575 }
13576 __tmp.put_u64_le(self.usec);
13577 __tmp.put_f32_le(self.x);
13578 __tmp.put_f32_le(self.y);
13579 __tmp.put_f32_le(self.z);
13580 __tmp.put_f32_le(self.roll);
13581 __tmp.put_f32_le(self.pitch);
13582 __tmp.put_f32_le(self.yaw);
13583 for val in &self.covariance {
13584 __tmp.put_f32_le(*val);
13585 }
13586 __tmp.put_u8(self.reset_counter);
13587 if matches!(version, MavlinkVersion::V2) {
13588 let len = __tmp.len();
13589 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13590 } else {
13591 __tmp.len()
13592 }
13593 }
13594}
13595#[doc = "id: 233"]
13596#[doc = "RTCM message for injecting into the onboard GPS (used for DGPS)."]
13597#[derive(Debug, Clone, PartialEq)]
13598#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13599#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13600pub struct GPS_RTCM_DATA_DATA {
13601 #[doc = "LSB: 1 means message is fragmented, next 2 bits are the fragment ID, the remaining 5 bits are used for the sequence ID. Messages are only to be flushed to the GPS when the entire message has been reconstructed on the autopilot. The fragment ID specifies which order the fragments should be assembled into a buffer, while the sequence ID is used to detect a mismatch between different buffers. The buffer is considered fully reconstructed when either all 4 fragments are present, or all the fragments before the first fragment with a non full payload is received. This management is used to ensure that normal GPS operation doesn't corrupt RTCM data, and to recover from a unreliable transport delivery order."]
13602 pub flags: u8,
13603 #[doc = "data length"]
13604 pub len: u8,
13605 #[doc = "RTCM message (may be fragmented)"]
13606 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
13607 pub data: [u8; 180],
13608}
13609impl GPS_RTCM_DATA_DATA {
13610 pub const ENCODED_LEN: usize = 182usize;
13611 pub const DEFAULT: Self = Self {
13612 flags: 0_u8,
13613 len: 0_u8,
13614 data: [0_u8; 180usize],
13615 };
13616 #[cfg(feature = "arbitrary")]
13617 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13618 use arbitrary::{Arbitrary, Unstructured};
13619 let mut buf = [0u8; 1024];
13620 rng.fill_bytes(&mut buf);
13621 let mut unstructured = Unstructured::new(&buf);
13622 Self::arbitrary(&mut unstructured).unwrap_or_default()
13623 }
13624}
13625impl Default for GPS_RTCM_DATA_DATA {
13626 fn default() -> Self {
13627 Self::DEFAULT.clone()
13628 }
13629}
13630impl MessageData for GPS_RTCM_DATA_DATA {
13631 type Message = MavMessage;
13632 const ID: u32 = 233u32;
13633 const NAME: &'static str = "GPS_RTCM_DATA";
13634 const EXTRA_CRC: u8 = 35u8;
13635 const ENCODED_LEN: usize = 182usize;
13636 fn deser(
13637 _version: MavlinkVersion,
13638 __input: &[u8],
13639 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13640 let avail_len = __input.len();
13641 let mut payload_buf = [0; Self::ENCODED_LEN];
13642 let mut buf = if avail_len < Self::ENCODED_LEN {
13643 payload_buf[0..avail_len].copy_from_slice(__input);
13644 Bytes::new(&payload_buf)
13645 } else {
13646 Bytes::new(__input)
13647 };
13648 let mut __struct = Self::default();
13649 __struct.flags = buf.get_u8();
13650 __struct.len = buf.get_u8();
13651 for v in &mut __struct.data {
13652 let val = buf.get_u8();
13653 *v = val;
13654 }
13655 Ok(__struct)
13656 }
13657 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13658 let mut __tmp = BytesMut::new(bytes);
13659 #[allow(clippy::absurd_extreme_comparisons)]
13660 #[allow(unused_comparisons)]
13661 if __tmp.remaining() < Self::ENCODED_LEN {
13662 panic!(
13663 "buffer is too small (need {} bytes, but got {})",
13664 Self::ENCODED_LEN,
13665 __tmp.remaining(),
13666 )
13667 }
13668 __tmp.put_u8(self.flags);
13669 __tmp.put_u8(self.len);
13670 for val in &self.data {
13671 __tmp.put_u8(*val);
13672 }
13673 if matches!(version, MavlinkVersion::V2) {
13674 let len = __tmp.len();
13675 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13676 } else {
13677 __tmp.len()
13678 }
13679 }
13680}
13681#[doc = "id: 249"]
13682#[doc = "Send raw controller memory. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output."]
13683#[derive(Debug, Clone, PartialEq)]
13684#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13685#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13686pub struct MEMORY_VECT_DATA {
13687 #[doc = "Starting address of the debug variables"]
13688 pub address: u16,
13689 #[doc = "Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below"]
13690 pub ver: u8,
13691 #[doc = "Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14"]
13692 pub mavtype: u8,
13693 #[doc = "Memory contents at specified address"]
13694 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
13695 pub value: [i8; 32],
13696}
13697impl MEMORY_VECT_DATA {
13698 pub const ENCODED_LEN: usize = 36usize;
13699 pub const DEFAULT: Self = Self {
13700 address: 0_u16,
13701 ver: 0_u8,
13702 mavtype: 0_u8,
13703 value: [0_i8; 32usize],
13704 };
13705 #[cfg(feature = "arbitrary")]
13706 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13707 use arbitrary::{Arbitrary, Unstructured};
13708 let mut buf = [0u8; 1024];
13709 rng.fill_bytes(&mut buf);
13710 let mut unstructured = Unstructured::new(&buf);
13711 Self::arbitrary(&mut unstructured).unwrap_or_default()
13712 }
13713}
13714impl Default for MEMORY_VECT_DATA {
13715 fn default() -> Self {
13716 Self::DEFAULT.clone()
13717 }
13718}
13719impl MessageData for MEMORY_VECT_DATA {
13720 type Message = MavMessage;
13721 const ID: u32 = 249u32;
13722 const NAME: &'static str = "MEMORY_VECT";
13723 const EXTRA_CRC: u8 = 204u8;
13724 const ENCODED_LEN: usize = 36usize;
13725 fn deser(
13726 _version: MavlinkVersion,
13727 __input: &[u8],
13728 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13729 let avail_len = __input.len();
13730 let mut payload_buf = [0; Self::ENCODED_LEN];
13731 let mut buf = if avail_len < Self::ENCODED_LEN {
13732 payload_buf[0..avail_len].copy_from_slice(__input);
13733 Bytes::new(&payload_buf)
13734 } else {
13735 Bytes::new(__input)
13736 };
13737 let mut __struct = Self::default();
13738 __struct.address = buf.get_u16_le();
13739 __struct.ver = buf.get_u8();
13740 __struct.mavtype = buf.get_u8();
13741 for v in &mut __struct.value {
13742 let val = buf.get_i8();
13743 *v = val;
13744 }
13745 Ok(__struct)
13746 }
13747 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13748 let mut __tmp = BytesMut::new(bytes);
13749 #[allow(clippy::absurd_extreme_comparisons)]
13750 #[allow(unused_comparisons)]
13751 if __tmp.remaining() < Self::ENCODED_LEN {
13752 panic!(
13753 "buffer is too small (need {} bytes, but got {})",
13754 Self::ENCODED_LEN,
13755 __tmp.remaining(),
13756 )
13757 }
13758 __tmp.put_u16_le(self.address);
13759 __tmp.put_u8(self.ver);
13760 __tmp.put_u8(self.mavtype);
13761 for val in &self.value {
13762 __tmp.put_i8(*val);
13763 }
13764 if matches!(version, MavlinkVersion::V2) {
13765 let len = __tmp.len();
13766 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13767 } else {
13768 __tmp.len()
13769 }
13770 }
13771}
13772#[doc = "id: 257"]
13773#[doc = "Report button state change."]
13774#[derive(Debug, Clone, PartialEq)]
13775#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13776#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13777pub struct BUTTON_CHANGE_DATA {
13778 #[doc = "Timestamp (time since system boot)."]
13779 pub time_boot_ms: u32,
13780 #[doc = "Time of last change of button state."]
13781 pub last_change_ms: u32,
13782 #[doc = "Bitmap for state of buttons."]
13783 pub state: u8,
13784}
13785impl BUTTON_CHANGE_DATA {
13786 pub const ENCODED_LEN: usize = 9usize;
13787 pub const DEFAULT: Self = Self {
13788 time_boot_ms: 0_u32,
13789 last_change_ms: 0_u32,
13790 state: 0_u8,
13791 };
13792 #[cfg(feature = "arbitrary")]
13793 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13794 use arbitrary::{Arbitrary, Unstructured};
13795 let mut buf = [0u8; 1024];
13796 rng.fill_bytes(&mut buf);
13797 let mut unstructured = Unstructured::new(&buf);
13798 Self::arbitrary(&mut unstructured).unwrap_or_default()
13799 }
13800}
13801impl Default for BUTTON_CHANGE_DATA {
13802 fn default() -> Self {
13803 Self::DEFAULT.clone()
13804 }
13805}
13806impl MessageData for BUTTON_CHANGE_DATA {
13807 type Message = MavMessage;
13808 const ID: u32 = 257u32;
13809 const NAME: &'static str = "BUTTON_CHANGE";
13810 const EXTRA_CRC: u8 = 131u8;
13811 const ENCODED_LEN: usize = 9usize;
13812 fn deser(
13813 _version: MavlinkVersion,
13814 __input: &[u8],
13815 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13816 let avail_len = __input.len();
13817 let mut payload_buf = [0; Self::ENCODED_LEN];
13818 let mut buf = if avail_len < Self::ENCODED_LEN {
13819 payload_buf[0..avail_len].copy_from_slice(__input);
13820 Bytes::new(&payload_buf)
13821 } else {
13822 Bytes::new(__input)
13823 };
13824 let mut __struct = Self::default();
13825 __struct.time_boot_ms = buf.get_u32_le();
13826 __struct.last_change_ms = buf.get_u32_le();
13827 __struct.state = buf.get_u8();
13828 Ok(__struct)
13829 }
13830 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13831 let mut __tmp = BytesMut::new(bytes);
13832 #[allow(clippy::absurd_extreme_comparisons)]
13833 #[allow(unused_comparisons)]
13834 if __tmp.remaining() < Self::ENCODED_LEN {
13835 panic!(
13836 "buffer is too small (need {} bytes, but got {})",
13837 Self::ENCODED_LEN,
13838 __tmp.remaining(),
13839 )
13840 }
13841 __tmp.put_u32_le(self.time_boot_ms);
13842 __tmp.put_u32_le(self.last_change_ms);
13843 __tmp.put_u8(self.state);
13844 if matches!(version, MavlinkVersion::V2) {
13845 let len = __tmp.len();
13846 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13847 } else {
13848 __tmp.len()
13849 }
13850 }
13851}
13852#[doc = "id: 340"]
13853#[doc = "The global position resulting from GPS and sensor fusion."]
13854#[derive(Debug, Clone, PartialEq)]
13855#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13856#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13857pub struct UTM_GLOBAL_POSITION_DATA {
13858 #[doc = "Time of applicability of position (microseconds since UNIX epoch)."]
13859 pub time: u64,
13860 #[doc = "Latitude (WGS84)"]
13861 pub lat: i32,
13862 #[doc = "Longitude (WGS84)"]
13863 pub lon: i32,
13864 #[doc = "Altitude (WGS84)"]
13865 pub alt: i32,
13866 #[doc = "Altitude above ground"]
13867 pub relative_alt: i32,
13868 #[doc = "Next waypoint, latitude (WGS84)"]
13869 pub next_lat: i32,
13870 #[doc = "Next waypoint, longitude (WGS84)"]
13871 pub next_lon: i32,
13872 #[doc = "Next waypoint, altitude (WGS84)"]
13873 pub next_alt: i32,
13874 #[doc = "Ground X speed (latitude, positive north)"]
13875 pub vx: i16,
13876 #[doc = "Ground Y speed (longitude, positive east)"]
13877 pub vy: i16,
13878 #[doc = "Ground Z speed (altitude, positive down)"]
13879 pub vz: i16,
13880 #[doc = "Horizontal position uncertainty (standard deviation)"]
13881 pub h_acc: u16,
13882 #[doc = "Altitude uncertainty (standard deviation)"]
13883 pub v_acc: u16,
13884 #[doc = "Speed uncertainty (standard deviation)"]
13885 pub vel_acc: u16,
13886 #[doc = "Time until next update. Set to 0 if unknown or in data driven mode."]
13887 pub update_rate: u16,
13888 #[doc = "Unique UAS ID."]
13889 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
13890 pub uas_id: [u8; 18],
13891 #[doc = "Flight state"]
13892 pub flight_state: UtmFlightState,
13893 #[doc = "Bitwise OR combination of the data available flags."]
13894 pub flags: UtmDataAvailFlags,
13895}
13896impl UTM_GLOBAL_POSITION_DATA {
13897 pub const ENCODED_LEN: usize = 70usize;
13898 pub const DEFAULT: Self = Self {
13899 time: 0_u64,
13900 lat: 0_i32,
13901 lon: 0_i32,
13902 alt: 0_i32,
13903 relative_alt: 0_i32,
13904 next_lat: 0_i32,
13905 next_lon: 0_i32,
13906 next_alt: 0_i32,
13907 vx: 0_i16,
13908 vy: 0_i16,
13909 vz: 0_i16,
13910 h_acc: 0_u16,
13911 v_acc: 0_u16,
13912 vel_acc: 0_u16,
13913 update_rate: 0_u16,
13914 uas_id: [0_u8; 18usize],
13915 flight_state: UtmFlightState::DEFAULT,
13916 flags: UtmDataAvailFlags::DEFAULT,
13917 };
13918 #[cfg(feature = "arbitrary")]
13919 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13920 use arbitrary::{Arbitrary, Unstructured};
13921 let mut buf = [0u8; 1024];
13922 rng.fill_bytes(&mut buf);
13923 let mut unstructured = Unstructured::new(&buf);
13924 Self::arbitrary(&mut unstructured).unwrap_or_default()
13925 }
13926}
13927impl Default for UTM_GLOBAL_POSITION_DATA {
13928 fn default() -> Self {
13929 Self::DEFAULT.clone()
13930 }
13931}
13932impl MessageData for UTM_GLOBAL_POSITION_DATA {
13933 type Message = MavMessage;
13934 const ID: u32 = 340u32;
13935 const NAME: &'static str = "UTM_GLOBAL_POSITION";
13936 const EXTRA_CRC: u8 = 99u8;
13937 const ENCODED_LEN: usize = 70usize;
13938 fn deser(
13939 _version: MavlinkVersion,
13940 __input: &[u8],
13941 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13942 let avail_len = __input.len();
13943 let mut payload_buf = [0; Self::ENCODED_LEN];
13944 let mut buf = if avail_len < Self::ENCODED_LEN {
13945 payload_buf[0..avail_len].copy_from_slice(__input);
13946 Bytes::new(&payload_buf)
13947 } else {
13948 Bytes::new(__input)
13949 };
13950 let mut __struct = Self::default();
13951 __struct.time = buf.get_u64_le();
13952 __struct.lat = buf.get_i32_le();
13953 __struct.lon = buf.get_i32_le();
13954 __struct.alt = buf.get_i32_le();
13955 __struct.relative_alt = buf.get_i32_le();
13956 __struct.next_lat = buf.get_i32_le();
13957 __struct.next_lon = buf.get_i32_le();
13958 __struct.next_alt = buf.get_i32_le();
13959 __struct.vx = buf.get_i16_le();
13960 __struct.vy = buf.get_i16_le();
13961 __struct.vz = buf.get_i16_le();
13962 __struct.h_acc = buf.get_u16_le();
13963 __struct.v_acc = buf.get_u16_le();
13964 __struct.vel_acc = buf.get_u16_le();
13965 __struct.update_rate = buf.get_u16_le();
13966 for v in &mut __struct.uas_id {
13967 let val = buf.get_u8();
13968 *v = val;
13969 }
13970 let tmp = buf.get_u8();
13971 __struct.flight_state =
13972 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
13973 enum_type: "UtmFlightState",
13974 value: tmp as u32,
13975 })?;
13976 let tmp = buf.get_u8();
13977 __struct.flags = UtmDataAvailFlags::from_bits(tmp & UtmDataAvailFlags::all().bits())
13978 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
13979 flag_type: "UtmDataAvailFlags",
13980 value: tmp as u32,
13981 })?;
13982 Ok(__struct)
13983 }
13984 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13985 let mut __tmp = BytesMut::new(bytes);
13986 #[allow(clippy::absurd_extreme_comparisons)]
13987 #[allow(unused_comparisons)]
13988 if __tmp.remaining() < Self::ENCODED_LEN {
13989 panic!(
13990 "buffer is too small (need {} bytes, but got {})",
13991 Self::ENCODED_LEN,
13992 __tmp.remaining(),
13993 )
13994 }
13995 __tmp.put_u64_le(self.time);
13996 __tmp.put_i32_le(self.lat);
13997 __tmp.put_i32_le(self.lon);
13998 __tmp.put_i32_le(self.alt);
13999 __tmp.put_i32_le(self.relative_alt);
14000 __tmp.put_i32_le(self.next_lat);
14001 __tmp.put_i32_le(self.next_lon);
14002 __tmp.put_i32_le(self.next_alt);
14003 __tmp.put_i16_le(self.vx);
14004 __tmp.put_i16_le(self.vy);
14005 __tmp.put_i16_le(self.vz);
14006 __tmp.put_u16_le(self.h_acc);
14007 __tmp.put_u16_le(self.v_acc);
14008 __tmp.put_u16_le(self.vel_acc);
14009 __tmp.put_u16_le(self.update_rate);
14010 for val in &self.uas_id {
14011 __tmp.put_u8(*val);
14012 }
14013 __tmp.put_u8(self.flight_state as u8);
14014 __tmp.put_u8(self.flags.bits());
14015 if matches!(version, MavlinkVersion::V2) {
14016 let len = __tmp.len();
14017 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14018 } else {
14019 __tmp.len()
14020 }
14021 }
14022}
14023#[doc = "id: 9000"]
14024#[doc = "Cumulative distance traveled for each reported wheel."]
14025#[derive(Debug, Clone, PartialEq)]
14026#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14027#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14028pub struct WHEEL_DISTANCE_DATA {
14029 #[doc = "Timestamp (synced to UNIX time or since system boot)."]
14030 pub time_usec: u64,
14031 #[doc = "Distance reported by individual wheel encoders. Forward rotations increase values, reverse rotations decrease them. Not all wheels will necessarily have wheel encoders; the mapping of encoders to wheel positions must be agreed/understood by the endpoints."]
14032 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
14033 pub distance: [f64; 16],
14034 #[doc = "Number of wheels reported."]
14035 pub count: u8,
14036}
14037impl WHEEL_DISTANCE_DATA {
14038 pub const ENCODED_LEN: usize = 137usize;
14039 pub const DEFAULT: Self = Self {
14040 time_usec: 0_u64,
14041 distance: [0.0_f64; 16usize],
14042 count: 0_u8,
14043 };
14044 #[cfg(feature = "arbitrary")]
14045 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14046 use arbitrary::{Arbitrary, Unstructured};
14047 let mut buf = [0u8; 1024];
14048 rng.fill_bytes(&mut buf);
14049 let mut unstructured = Unstructured::new(&buf);
14050 Self::arbitrary(&mut unstructured).unwrap_or_default()
14051 }
14052}
14053impl Default for WHEEL_DISTANCE_DATA {
14054 fn default() -> Self {
14055 Self::DEFAULT.clone()
14056 }
14057}
14058impl MessageData for WHEEL_DISTANCE_DATA {
14059 type Message = MavMessage;
14060 const ID: u32 = 9000u32;
14061 const NAME: &'static str = "WHEEL_DISTANCE";
14062 const EXTRA_CRC: u8 = 113u8;
14063 const ENCODED_LEN: usize = 137usize;
14064 fn deser(
14065 _version: MavlinkVersion,
14066 __input: &[u8],
14067 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14068 let avail_len = __input.len();
14069 let mut payload_buf = [0; Self::ENCODED_LEN];
14070 let mut buf = if avail_len < Self::ENCODED_LEN {
14071 payload_buf[0..avail_len].copy_from_slice(__input);
14072 Bytes::new(&payload_buf)
14073 } else {
14074 Bytes::new(__input)
14075 };
14076 let mut __struct = Self::default();
14077 __struct.time_usec = buf.get_u64_le();
14078 for v in &mut __struct.distance {
14079 let val = buf.get_f64_le();
14080 *v = val;
14081 }
14082 __struct.count = buf.get_u8();
14083 Ok(__struct)
14084 }
14085 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14086 let mut __tmp = BytesMut::new(bytes);
14087 #[allow(clippy::absurd_extreme_comparisons)]
14088 #[allow(unused_comparisons)]
14089 if __tmp.remaining() < Self::ENCODED_LEN {
14090 panic!(
14091 "buffer is too small (need {} bytes, but got {})",
14092 Self::ENCODED_LEN,
14093 __tmp.remaining(),
14094 )
14095 }
14096 __tmp.put_u64_le(self.time_usec);
14097 for val in &self.distance {
14098 __tmp.put_f64_le(*val);
14099 }
14100 __tmp.put_u8(self.count);
14101 if matches!(version, MavlinkVersion::V2) {
14102 let len = __tmp.len();
14103 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14104 } else {
14105 __tmp.len()
14106 }
14107 }
14108}
14109#[doc = "id: 105"]
14110#[doc = "The IMU readings in SI units in NED body frame."]
14111#[derive(Debug, Clone, PartialEq)]
14112#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14113#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14114pub struct HIGHRES_IMU_DATA {
14115 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
14116 pub time_usec: u64,
14117 #[doc = "X acceleration"]
14118 pub xacc: f32,
14119 #[doc = "Y acceleration"]
14120 pub yacc: f32,
14121 #[doc = "Z acceleration"]
14122 pub zacc: f32,
14123 #[doc = "Angular speed around X axis"]
14124 pub xgyro: f32,
14125 #[doc = "Angular speed around Y axis"]
14126 pub ygyro: f32,
14127 #[doc = "Angular speed around Z axis"]
14128 pub zgyro: f32,
14129 #[doc = "X Magnetic field"]
14130 pub xmag: f32,
14131 #[doc = "Y Magnetic field"]
14132 pub ymag: f32,
14133 #[doc = "Z Magnetic field"]
14134 pub zmag: f32,
14135 #[doc = "Absolute pressure"]
14136 pub abs_pressure: f32,
14137 #[doc = "Differential pressure"]
14138 pub diff_pressure: f32,
14139 #[doc = "Altitude calculated from pressure"]
14140 pub pressure_alt: f32,
14141 #[doc = "Temperature"]
14142 pub temperature: f32,
14143 #[doc = "Bitmap for fields that have updated since last message"]
14144 pub fields_updated: HighresImuUpdatedFlags,
14145 #[doc = "Id. Ids are numbered from 0 and map to IMUs numbered from 1 (e.g. IMU1 will have a message with id=0)"]
14146 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
14147 pub id: u8,
14148}
14149impl HIGHRES_IMU_DATA {
14150 pub const ENCODED_LEN: usize = 63usize;
14151 pub const DEFAULT: Self = Self {
14152 time_usec: 0_u64,
14153 xacc: 0.0_f32,
14154 yacc: 0.0_f32,
14155 zacc: 0.0_f32,
14156 xgyro: 0.0_f32,
14157 ygyro: 0.0_f32,
14158 zgyro: 0.0_f32,
14159 xmag: 0.0_f32,
14160 ymag: 0.0_f32,
14161 zmag: 0.0_f32,
14162 abs_pressure: 0.0_f32,
14163 diff_pressure: 0.0_f32,
14164 pressure_alt: 0.0_f32,
14165 temperature: 0.0_f32,
14166 fields_updated: HighresImuUpdatedFlags::DEFAULT,
14167 id: 0_u8,
14168 };
14169 #[cfg(feature = "arbitrary")]
14170 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14171 use arbitrary::{Arbitrary, Unstructured};
14172 let mut buf = [0u8; 1024];
14173 rng.fill_bytes(&mut buf);
14174 let mut unstructured = Unstructured::new(&buf);
14175 Self::arbitrary(&mut unstructured).unwrap_or_default()
14176 }
14177}
14178impl Default for HIGHRES_IMU_DATA {
14179 fn default() -> Self {
14180 Self::DEFAULT.clone()
14181 }
14182}
14183impl MessageData for HIGHRES_IMU_DATA {
14184 type Message = MavMessage;
14185 const ID: u32 = 105u32;
14186 const NAME: &'static str = "HIGHRES_IMU";
14187 const EXTRA_CRC: u8 = 93u8;
14188 const ENCODED_LEN: usize = 63usize;
14189 fn deser(
14190 _version: MavlinkVersion,
14191 __input: &[u8],
14192 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14193 let avail_len = __input.len();
14194 let mut payload_buf = [0; Self::ENCODED_LEN];
14195 let mut buf = if avail_len < Self::ENCODED_LEN {
14196 payload_buf[0..avail_len].copy_from_slice(__input);
14197 Bytes::new(&payload_buf)
14198 } else {
14199 Bytes::new(__input)
14200 };
14201 let mut __struct = Self::default();
14202 __struct.time_usec = buf.get_u64_le();
14203 __struct.xacc = buf.get_f32_le();
14204 __struct.yacc = buf.get_f32_le();
14205 __struct.zacc = buf.get_f32_le();
14206 __struct.xgyro = buf.get_f32_le();
14207 __struct.ygyro = buf.get_f32_le();
14208 __struct.zgyro = buf.get_f32_le();
14209 __struct.xmag = buf.get_f32_le();
14210 __struct.ymag = buf.get_f32_le();
14211 __struct.zmag = buf.get_f32_le();
14212 __struct.abs_pressure = buf.get_f32_le();
14213 __struct.diff_pressure = buf.get_f32_le();
14214 __struct.pressure_alt = buf.get_f32_le();
14215 __struct.temperature = buf.get_f32_le();
14216 let tmp = buf.get_u16_le();
14217 __struct.fields_updated = HighresImuUpdatedFlags::from_bits(
14218 tmp & HighresImuUpdatedFlags::all().bits(),
14219 )
14220 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
14221 flag_type: "HighresImuUpdatedFlags",
14222 value: tmp as u32,
14223 })?;
14224 __struct.id = buf.get_u8();
14225 Ok(__struct)
14226 }
14227 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14228 let mut __tmp = BytesMut::new(bytes);
14229 #[allow(clippy::absurd_extreme_comparisons)]
14230 #[allow(unused_comparisons)]
14231 if __tmp.remaining() < Self::ENCODED_LEN {
14232 panic!(
14233 "buffer is too small (need {} bytes, but got {})",
14234 Self::ENCODED_LEN,
14235 __tmp.remaining(),
14236 )
14237 }
14238 __tmp.put_u64_le(self.time_usec);
14239 __tmp.put_f32_le(self.xacc);
14240 __tmp.put_f32_le(self.yacc);
14241 __tmp.put_f32_le(self.zacc);
14242 __tmp.put_f32_le(self.xgyro);
14243 __tmp.put_f32_le(self.ygyro);
14244 __tmp.put_f32_le(self.zgyro);
14245 __tmp.put_f32_le(self.xmag);
14246 __tmp.put_f32_le(self.ymag);
14247 __tmp.put_f32_le(self.zmag);
14248 __tmp.put_f32_le(self.abs_pressure);
14249 __tmp.put_f32_le(self.diff_pressure);
14250 __tmp.put_f32_le(self.pressure_alt);
14251 __tmp.put_f32_le(self.temperature);
14252 __tmp.put_u16_le(self.fields_updated.bits());
14253 __tmp.put_u8(self.id);
14254 if matches!(version, MavlinkVersion::V2) {
14255 let len = __tmp.len();
14256 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14257 } else {
14258 __tmp.len()
14259 }
14260 }
14261}
14262#[doc = "id: 112"]
14263#[doc = "Camera-IMU triggering and synchronisation message."]
14264#[derive(Debug, Clone, PartialEq)]
14265#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14266#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14267pub struct CAMERA_TRIGGER_DATA {
14268 #[doc = "Timestamp for image frame (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
14269 pub time_usec: u64,
14270 #[doc = "Image frame sequence"]
14271 pub seq: u32,
14272}
14273impl CAMERA_TRIGGER_DATA {
14274 pub const ENCODED_LEN: usize = 12usize;
14275 pub const DEFAULT: Self = Self {
14276 time_usec: 0_u64,
14277 seq: 0_u32,
14278 };
14279 #[cfg(feature = "arbitrary")]
14280 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14281 use arbitrary::{Arbitrary, Unstructured};
14282 let mut buf = [0u8; 1024];
14283 rng.fill_bytes(&mut buf);
14284 let mut unstructured = Unstructured::new(&buf);
14285 Self::arbitrary(&mut unstructured).unwrap_or_default()
14286 }
14287}
14288impl Default for CAMERA_TRIGGER_DATA {
14289 fn default() -> Self {
14290 Self::DEFAULT.clone()
14291 }
14292}
14293impl MessageData for CAMERA_TRIGGER_DATA {
14294 type Message = MavMessage;
14295 const ID: u32 = 112u32;
14296 const NAME: &'static str = "CAMERA_TRIGGER";
14297 const EXTRA_CRC: u8 = 174u8;
14298 const ENCODED_LEN: usize = 12usize;
14299 fn deser(
14300 _version: MavlinkVersion,
14301 __input: &[u8],
14302 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14303 let avail_len = __input.len();
14304 let mut payload_buf = [0; Self::ENCODED_LEN];
14305 let mut buf = if avail_len < Self::ENCODED_LEN {
14306 payload_buf[0..avail_len].copy_from_slice(__input);
14307 Bytes::new(&payload_buf)
14308 } else {
14309 Bytes::new(__input)
14310 };
14311 let mut __struct = Self::default();
14312 __struct.time_usec = buf.get_u64_le();
14313 __struct.seq = buf.get_u32_le();
14314 Ok(__struct)
14315 }
14316 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14317 let mut __tmp = BytesMut::new(bytes);
14318 #[allow(clippy::absurd_extreme_comparisons)]
14319 #[allow(unused_comparisons)]
14320 if __tmp.remaining() < Self::ENCODED_LEN {
14321 panic!(
14322 "buffer is too small (need {} bytes, but got {})",
14323 Self::ENCODED_LEN,
14324 __tmp.remaining(),
14325 )
14326 }
14327 __tmp.put_u64_le(self.time_usec);
14328 __tmp.put_u32_le(self.seq);
14329 if matches!(version, MavlinkVersion::V2) {
14330 let len = __tmp.len();
14331 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14332 } else {
14333 __tmp.len()
14334 }
14335 }
14336}
14337#[doc = "id: 123"]
14338#[doc = "Data for injecting into the onboard GPS (used for DGPS)."]
14339#[derive(Debug, Clone, PartialEq)]
14340#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14341#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14342pub struct GPS_INJECT_DATA_DATA {
14343 #[doc = "System ID"]
14344 pub target_system: u8,
14345 #[doc = "Component ID"]
14346 pub target_component: u8,
14347 #[doc = "Data length"]
14348 pub len: u8,
14349 #[doc = "Raw data (110 is enough for 12 satellites of RTCMv2)"]
14350 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
14351 pub data: [u8; 110],
14352}
14353impl GPS_INJECT_DATA_DATA {
14354 pub const ENCODED_LEN: usize = 113usize;
14355 pub const DEFAULT: Self = Self {
14356 target_system: 0_u8,
14357 target_component: 0_u8,
14358 len: 0_u8,
14359 data: [0_u8; 110usize],
14360 };
14361 #[cfg(feature = "arbitrary")]
14362 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14363 use arbitrary::{Arbitrary, Unstructured};
14364 let mut buf = [0u8; 1024];
14365 rng.fill_bytes(&mut buf);
14366 let mut unstructured = Unstructured::new(&buf);
14367 Self::arbitrary(&mut unstructured).unwrap_or_default()
14368 }
14369}
14370impl Default for GPS_INJECT_DATA_DATA {
14371 fn default() -> Self {
14372 Self::DEFAULT.clone()
14373 }
14374}
14375impl MessageData for GPS_INJECT_DATA_DATA {
14376 type Message = MavMessage;
14377 const ID: u32 = 123u32;
14378 const NAME: &'static str = "GPS_INJECT_DATA";
14379 const EXTRA_CRC: u8 = 250u8;
14380 const ENCODED_LEN: usize = 113usize;
14381 fn deser(
14382 _version: MavlinkVersion,
14383 __input: &[u8],
14384 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14385 let avail_len = __input.len();
14386 let mut payload_buf = [0; Self::ENCODED_LEN];
14387 let mut buf = if avail_len < Self::ENCODED_LEN {
14388 payload_buf[0..avail_len].copy_from_slice(__input);
14389 Bytes::new(&payload_buf)
14390 } else {
14391 Bytes::new(__input)
14392 };
14393 let mut __struct = Self::default();
14394 __struct.target_system = buf.get_u8();
14395 __struct.target_component = buf.get_u8();
14396 __struct.len = buf.get_u8();
14397 for v in &mut __struct.data {
14398 let val = buf.get_u8();
14399 *v = val;
14400 }
14401 Ok(__struct)
14402 }
14403 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14404 let mut __tmp = BytesMut::new(bytes);
14405 #[allow(clippy::absurd_extreme_comparisons)]
14406 #[allow(unused_comparisons)]
14407 if __tmp.remaining() < Self::ENCODED_LEN {
14408 panic!(
14409 "buffer is too small (need {} bytes, but got {})",
14410 Self::ENCODED_LEN,
14411 __tmp.remaining(),
14412 )
14413 }
14414 __tmp.put_u8(self.target_system);
14415 __tmp.put_u8(self.target_component);
14416 __tmp.put_u8(self.len);
14417 for val in &self.data {
14418 __tmp.put_u8(*val);
14419 }
14420 if matches!(version, MavlinkVersion::V2) {
14421 let len = __tmp.len();
14422 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14423 } else {
14424 __tmp.len()
14425 }
14426 }
14427}
14428#[doc = "id: 277"]
14429#[doc = "Camera absolute thermal range. This can be streamed when the associated VIDEO_STREAM_STATUS `flag` field bit VIDEO_STREAM_STATUS_FLAGS_THERMAL_RANGE_ENABLED is set, but a GCS may choose to only request it for the current active stream. Use MAV_CMD_SET_MESSAGE_INTERVAL to define message interval (param3 indicates the stream id of the current camera, or 0 for all streams, param4 indicates the target camera_device_id for autopilot-attached cameras or 0 for MAVLink cameras)."]
14430#[derive(Debug, Clone, PartialEq)]
14431#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14432#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14433pub struct CAMERA_THERMAL_RANGE_DATA {
14434 #[doc = "Timestamp (time since system boot)."]
14435 pub time_boot_ms: u32,
14436 #[doc = "Temperature max."]
14437 pub max: f32,
14438 #[doc = "Temperature max point x value (normalized 0..1, 0 is left, 1 is right), NAN if unknown."]
14439 pub max_point_x: f32,
14440 #[doc = "Temperature max point y value (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown."]
14441 pub max_point_y: f32,
14442 #[doc = "Temperature min."]
14443 pub min: f32,
14444 #[doc = "Temperature min point x value (normalized 0..1, 0 is left, 1 is right), NAN if unknown."]
14445 pub min_point_x: f32,
14446 #[doc = "Temperature min point y value (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown."]
14447 pub min_point_y: f32,
14448 #[doc = "Video Stream ID (1 for first, 2 for second, etc.)"]
14449 pub stream_id: u8,
14450 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
14451 pub camera_device_id: u8,
14452}
14453impl CAMERA_THERMAL_RANGE_DATA {
14454 pub const ENCODED_LEN: usize = 30usize;
14455 pub const DEFAULT: Self = Self {
14456 time_boot_ms: 0_u32,
14457 max: 0.0_f32,
14458 max_point_x: 0.0_f32,
14459 max_point_y: 0.0_f32,
14460 min: 0.0_f32,
14461 min_point_x: 0.0_f32,
14462 min_point_y: 0.0_f32,
14463 stream_id: 0_u8,
14464 camera_device_id: 0_u8,
14465 };
14466 #[cfg(feature = "arbitrary")]
14467 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14468 use arbitrary::{Arbitrary, Unstructured};
14469 let mut buf = [0u8; 1024];
14470 rng.fill_bytes(&mut buf);
14471 let mut unstructured = Unstructured::new(&buf);
14472 Self::arbitrary(&mut unstructured).unwrap_or_default()
14473 }
14474}
14475impl Default for CAMERA_THERMAL_RANGE_DATA {
14476 fn default() -> Self {
14477 Self::DEFAULT.clone()
14478 }
14479}
14480impl MessageData for CAMERA_THERMAL_RANGE_DATA {
14481 type Message = MavMessage;
14482 const ID: u32 = 277u32;
14483 const NAME: &'static str = "CAMERA_THERMAL_RANGE";
14484 const EXTRA_CRC: u8 = 62u8;
14485 const ENCODED_LEN: usize = 30usize;
14486 fn deser(
14487 _version: MavlinkVersion,
14488 __input: &[u8],
14489 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14490 let avail_len = __input.len();
14491 let mut payload_buf = [0; Self::ENCODED_LEN];
14492 let mut buf = if avail_len < Self::ENCODED_LEN {
14493 payload_buf[0..avail_len].copy_from_slice(__input);
14494 Bytes::new(&payload_buf)
14495 } else {
14496 Bytes::new(__input)
14497 };
14498 let mut __struct = Self::default();
14499 __struct.time_boot_ms = buf.get_u32_le();
14500 __struct.max = buf.get_f32_le();
14501 __struct.max_point_x = buf.get_f32_le();
14502 __struct.max_point_y = buf.get_f32_le();
14503 __struct.min = buf.get_f32_le();
14504 __struct.min_point_x = buf.get_f32_le();
14505 __struct.min_point_y = buf.get_f32_le();
14506 __struct.stream_id = buf.get_u8();
14507 __struct.camera_device_id = buf.get_u8();
14508 Ok(__struct)
14509 }
14510 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14511 let mut __tmp = BytesMut::new(bytes);
14512 #[allow(clippy::absurd_extreme_comparisons)]
14513 #[allow(unused_comparisons)]
14514 if __tmp.remaining() < Self::ENCODED_LEN {
14515 panic!(
14516 "buffer is too small (need {} bytes, but got {})",
14517 Self::ENCODED_LEN,
14518 __tmp.remaining(),
14519 )
14520 }
14521 __tmp.put_u32_le(self.time_boot_ms);
14522 __tmp.put_f32_le(self.max);
14523 __tmp.put_f32_le(self.max_point_x);
14524 __tmp.put_f32_le(self.max_point_y);
14525 __tmp.put_f32_le(self.min);
14526 __tmp.put_f32_le(self.min_point_x);
14527 __tmp.put_f32_le(self.min_point_y);
14528 __tmp.put_u8(self.stream_id);
14529 __tmp.put_u8(self.camera_device_id);
14530 if matches!(version, MavlinkVersion::V2) {
14531 let len = __tmp.len();
14532 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14533 } else {
14534 __tmp.len()
14535 }
14536 }
14537}
14538#[doc = "id: 339"]
14539#[doc = "RPM sensor data message."]
14540#[derive(Debug, Clone, PartialEq)]
14541#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14542#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14543pub struct RAW_RPM_DATA {
14544 #[doc = "Indicated rate"]
14545 pub frequency: f32,
14546 #[doc = "Index of this RPM sensor (0-indexed)"]
14547 pub index: u8,
14548}
14549impl RAW_RPM_DATA {
14550 pub const ENCODED_LEN: usize = 5usize;
14551 pub const DEFAULT: Self = Self {
14552 frequency: 0.0_f32,
14553 index: 0_u8,
14554 };
14555 #[cfg(feature = "arbitrary")]
14556 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14557 use arbitrary::{Arbitrary, Unstructured};
14558 let mut buf = [0u8; 1024];
14559 rng.fill_bytes(&mut buf);
14560 let mut unstructured = Unstructured::new(&buf);
14561 Self::arbitrary(&mut unstructured).unwrap_or_default()
14562 }
14563}
14564impl Default for RAW_RPM_DATA {
14565 fn default() -> Self {
14566 Self::DEFAULT.clone()
14567 }
14568}
14569impl MessageData for RAW_RPM_DATA {
14570 type Message = MavMessage;
14571 const ID: u32 = 339u32;
14572 const NAME: &'static str = "RAW_RPM";
14573 const EXTRA_CRC: u8 = 199u8;
14574 const ENCODED_LEN: usize = 5usize;
14575 fn deser(
14576 _version: MavlinkVersion,
14577 __input: &[u8],
14578 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14579 let avail_len = __input.len();
14580 let mut payload_buf = [0; Self::ENCODED_LEN];
14581 let mut buf = if avail_len < Self::ENCODED_LEN {
14582 payload_buf[0..avail_len].copy_from_slice(__input);
14583 Bytes::new(&payload_buf)
14584 } else {
14585 Bytes::new(__input)
14586 };
14587 let mut __struct = Self::default();
14588 __struct.frequency = buf.get_f32_le();
14589 __struct.index = buf.get_u8();
14590 Ok(__struct)
14591 }
14592 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14593 let mut __tmp = BytesMut::new(bytes);
14594 #[allow(clippy::absurd_extreme_comparisons)]
14595 #[allow(unused_comparisons)]
14596 if __tmp.remaining() < Self::ENCODED_LEN {
14597 panic!(
14598 "buffer is too small (need {} bytes, but got {})",
14599 Self::ENCODED_LEN,
14600 __tmp.remaining(),
14601 )
14602 }
14603 __tmp.put_f32_le(self.frequency);
14604 __tmp.put_u8(self.index);
14605 if matches!(version, MavlinkVersion::V2) {
14606 let len = __tmp.len();
14607 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14608 } else {
14609 __tmp.len()
14610 }
14611 }
14612}
14613#[doc = "id: 412"]
14614#[doc = "Request one or more events to be (re-)sent. If first_sequence==last_sequence, only a single event is requested. Note that first_sequence can be larger than last_sequence (because the sequence number can wrap). Each sequence will trigger an EVENT or EVENT_ERROR response."]
14615#[derive(Debug, Clone, PartialEq)]
14616#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14617#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14618pub struct REQUEST_EVENT_DATA {
14619 #[doc = "First sequence number of the requested event."]
14620 pub first_sequence: u16,
14621 #[doc = "Last sequence number of the requested event."]
14622 pub last_sequence: u16,
14623 #[doc = "System ID"]
14624 pub target_system: u8,
14625 #[doc = "Component ID"]
14626 pub target_component: u8,
14627}
14628impl REQUEST_EVENT_DATA {
14629 pub const ENCODED_LEN: usize = 6usize;
14630 pub const DEFAULT: Self = Self {
14631 first_sequence: 0_u16,
14632 last_sequence: 0_u16,
14633 target_system: 0_u8,
14634 target_component: 0_u8,
14635 };
14636 #[cfg(feature = "arbitrary")]
14637 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14638 use arbitrary::{Arbitrary, Unstructured};
14639 let mut buf = [0u8; 1024];
14640 rng.fill_bytes(&mut buf);
14641 let mut unstructured = Unstructured::new(&buf);
14642 Self::arbitrary(&mut unstructured).unwrap_or_default()
14643 }
14644}
14645impl Default for REQUEST_EVENT_DATA {
14646 fn default() -> Self {
14647 Self::DEFAULT.clone()
14648 }
14649}
14650impl MessageData for REQUEST_EVENT_DATA {
14651 type Message = MavMessage;
14652 const ID: u32 = 412u32;
14653 const NAME: &'static str = "REQUEST_EVENT";
14654 const EXTRA_CRC: u8 = 33u8;
14655 const ENCODED_LEN: usize = 6usize;
14656 fn deser(
14657 _version: MavlinkVersion,
14658 __input: &[u8],
14659 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14660 let avail_len = __input.len();
14661 let mut payload_buf = [0; Self::ENCODED_LEN];
14662 let mut buf = if avail_len < Self::ENCODED_LEN {
14663 payload_buf[0..avail_len].copy_from_slice(__input);
14664 Bytes::new(&payload_buf)
14665 } else {
14666 Bytes::new(__input)
14667 };
14668 let mut __struct = Self::default();
14669 __struct.first_sequence = buf.get_u16_le();
14670 __struct.last_sequence = buf.get_u16_le();
14671 __struct.target_system = buf.get_u8();
14672 __struct.target_component = buf.get_u8();
14673 Ok(__struct)
14674 }
14675 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14676 let mut __tmp = BytesMut::new(bytes);
14677 #[allow(clippy::absurd_extreme_comparisons)]
14678 #[allow(unused_comparisons)]
14679 if __tmp.remaining() < Self::ENCODED_LEN {
14680 panic!(
14681 "buffer is too small (need {} bytes, but got {})",
14682 Self::ENCODED_LEN,
14683 __tmp.remaining(),
14684 )
14685 }
14686 __tmp.put_u16_le(self.first_sequence);
14687 __tmp.put_u16_le(self.last_sequence);
14688 __tmp.put_u8(self.target_system);
14689 __tmp.put_u8(self.target_component);
14690 if matches!(version, MavlinkVersion::V2) {
14691 let len = __tmp.len();
14692 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14693 } else {
14694 __tmp.len()
14695 }
14696 }
14697}
14698#[doc = "id: 64"]
14699#[doc = "The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention)."]
14700#[derive(Debug, Clone, PartialEq)]
14701#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14702#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14703pub struct LOCAL_POSITION_NED_COV_DATA {
14704 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
14705 pub time_usec: u64,
14706 #[doc = "X Position"]
14707 pub x: f32,
14708 #[doc = "Y Position"]
14709 pub y: f32,
14710 #[doc = "Z Position"]
14711 pub z: f32,
14712 #[doc = "X Speed"]
14713 pub vx: f32,
14714 #[doc = "Y Speed"]
14715 pub vy: f32,
14716 #[doc = "Z Speed"]
14717 pub vz: f32,
14718 #[doc = "X Acceleration"]
14719 pub ax: f32,
14720 #[doc = "Y Acceleration"]
14721 pub ay: f32,
14722 #[doc = "Z Acceleration"]
14723 pub az: f32,
14724 #[doc = "Row-major representation of position, velocity and acceleration 9x9 cross-covariance matrix upper right triangle (states: x, y, z, vx, vy, vz, ax, ay, az; first nine entries are the first ROW, next eight entries are the second row, etc.). If unknown, assign NaN value to first element in the array."]
14725 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
14726 pub covariance: [f32; 45],
14727 #[doc = "Class id of the estimator this estimate originated from."]
14728 pub estimator_type: MavEstimatorType,
14729}
14730impl LOCAL_POSITION_NED_COV_DATA {
14731 pub const ENCODED_LEN: usize = 225usize;
14732 pub const DEFAULT: Self = Self {
14733 time_usec: 0_u64,
14734 x: 0.0_f32,
14735 y: 0.0_f32,
14736 z: 0.0_f32,
14737 vx: 0.0_f32,
14738 vy: 0.0_f32,
14739 vz: 0.0_f32,
14740 ax: 0.0_f32,
14741 ay: 0.0_f32,
14742 az: 0.0_f32,
14743 covariance: [0.0_f32; 45usize],
14744 estimator_type: MavEstimatorType::DEFAULT,
14745 };
14746 #[cfg(feature = "arbitrary")]
14747 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14748 use arbitrary::{Arbitrary, Unstructured};
14749 let mut buf = [0u8; 1024];
14750 rng.fill_bytes(&mut buf);
14751 let mut unstructured = Unstructured::new(&buf);
14752 Self::arbitrary(&mut unstructured).unwrap_or_default()
14753 }
14754}
14755impl Default for LOCAL_POSITION_NED_COV_DATA {
14756 fn default() -> Self {
14757 Self::DEFAULT.clone()
14758 }
14759}
14760impl MessageData for LOCAL_POSITION_NED_COV_DATA {
14761 type Message = MavMessage;
14762 const ID: u32 = 64u32;
14763 const NAME: &'static str = "LOCAL_POSITION_NED_COV";
14764 const EXTRA_CRC: u8 = 191u8;
14765 const ENCODED_LEN: usize = 225usize;
14766 fn deser(
14767 _version: MavlinkVersion,
14768 __input: &[u8],
14769 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14770 let avail_len = __input.len();
14771 let mut payload_buf = [0; Self::ENCODED_LEN];
14772 let mut buf = if avail_len < Self::ENCODED_LEN {
14773 payload_buf[0..avail_len].copy_from_slice(__input);
14774 Bytes::new(&payload_buf)
14775 } else {
14776 Bytes::new(__input)
14777 };
14778 let mut __struct = Self::default();
14779 __struct.time_usec = buf.get_u64_le();
14780 __struct.x = buf.get_f32_le();
14781 __struct.y = buf.get_f32_le();
14782 __struct.z = buf.get_f32_le();
14783 __struct.vx = buf.get_f32_le();
14784 __struct.vy = buf.get_f32_le();
14785 __struct.vz = buf.get_f32_le();
14786 __struct.ax = buf.get_f32_le();
14787 __struct.ay = buf.get_f32_le();
14788 __struct.az = buf.get_f32_le();
14789 for v in &mut __struct.covariance {
14790 let val = buf.get_f32_le();
14791 *v = val;
14792 }
14793 let tmp = buf.get_u8();
14794 __struct.estimator_type =
14795 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
14796 enum_type: "MavEstimatorType",
14797 value: tmp as u32,
14798 })?;
14799 Ok(__struct)
14800 }
14801 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14802 let mut __tmp = BytesMut::new(bytes);
14803 #[allow(clippy::absurd_extreme_comparisons)]
14804 #[allow(unused_comparisons)]
14805 if __tmp.remaining() < Self::ENCODED_LEN {
14806 panic!(
14807 "buffer is too small (need {} bytes, but got {})",
14808 Self::ENCODED_LEN,
14809 __tmp.remaining(),
14810 )
14811 }
14812 __tmp.put_u64_le(self.time_usec);
14813 __tmp.put_f32_le(self.x);
14814 __tmp.put_f32_le(self.y);
14815 __tmp.put_f32_le(self.z);
14816 __tmp.put_f32_le(self.vx);
14817 __tmp.put_f32_le(self.vy);
14818 __tmp.put_f32_le(self.vz);
14819 __tmp.put_f32_le(self.ax);
14820 __tmp.put_f32_le(self.ay);
14821 __tmp.put_f32_le(self.az);
14822 for val in &self.covariance {
14823 __tmp.put_f32_le(*val);
14824 }
14825 __tmp.put_u8(self.estimator_type as u8);
14826 if matches!(version, MavlinkVersion::V2) {
14827 let len = __tmp.len();
14828 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14829 } else {
14830 __tmp.len()
14831 }
14832 }
14833}
14834#[doc = "id: 63"]
14835#[doc = "The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up). It is designed as scaled integer message since the resolution of float is not sufficient. NOTE: This message is intended for onboard networks / companion computers and higher-bandwidth links and optimized for accuracy and completeness. Please use the GLOBAL_POSITION_INT message for a minimal subset."]
14836#[derive(Debug, Clone, PartialEq)]
14837#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14838#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14839pub struct GLOBAL_POSITION_INT_COV_DATA {
14840 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
14841 pub time_usec: u64,
14842 #[doc = "Latitude"]
14843 pub lat: i32,
14844 #[doc = "Longitude"]
14845 pub lon: i32,
14846 #[doc = "Altitude in meters above MSL"]
14847 pub alt: i32,
14848 #[doc = "Altitude above ground"]
14849 pub relative_alt: i32,
14850 #[doc = "Ground X Speed (Latitude)"]
14851 pub vx: f32,
14852 #[doc = "Ground Y Speed (Longitude)"]
14853 pub vy: f32,
14854 #[doc = "Ground Z Speed (Altitude)"]
14855 pub vz: f32,
14856 #[doc = "Row-major representation of a 6x6 position and velocity 6x6 cross-covariance matrix (states: lat, lon, alt, vx, vy, vz; first six entries are the first ROW, next six entries are the second row, etc.). If unknown, assign NaN value to first element in the array."]
14857 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
14858 pub covariance: [f32; 36],
14859 #[doc = "Class id of the estimator this estimate originated from."]
14860 pub estimator_type: MavEstimatorType,
14861}
14862impl GLOBAL_POSITION_INT_COV_DATA {
14863 pub const ENCODED_LEN: usize = 181usize;
14864 pub const DEFAULT: Self = Self {
14865 time_usec: 0_u64,
14866 lat: 0_i32,
14867 lon: 0_i32,
14868 alt: 0_i32,
14869 relative_alt: 0_i32,
14870 vx: 0.0_f32,
14871 vy: 0.0_f32,
14872 vz: 0.0_f32,
14873 covariance: [0.0_f32; 36usize],
14874 estimator_type: MavEstimatorType::DEFAULT,
14875 };
14876 #[cfg(feature = "arbitrary")]
14877 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14878 use arbitrary::{Arbitrary, Unstructured};
14879 let mut buf = [0u8; 1024];
14880 rng.fill_bytes(&mut buf);
14881 let mut unstructured = Unstructured::new(&buf);
14882 Self::arbitrary(&mut unstructured).unwrap_or_default()
14883 }
14884}
14885impl Default for GLOBAL_POSITION_INT_COV_DATA {
14886 fn default() -> Self {
14887 Self::DEFAULT.clone()
14888 }
14889}
14890impl MessageData for GLOBAL_POSITION_INT_COV_DATA {
14891 type Message = MavMessage;
14892 const ID: u32 = 63u32;
14893 const NAME: &'static str = "GLOBAL_POSITION_INT_COV";
14894 const EXTRA_CRC: u8 = 119u8;
14895 const ENCODED_LEN: usize = 181usize;
14896 fn deser(
14897 _version: MavlinkVersion,
14898 __input: &[u8],
14899 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14900 let avail_len = __input.len();
14901 let mut payload_buf = [0; Self::ENCODED_LEN];
14902 let mut buf = if avail_len < Self::ENCODED_LEN {
14903 payload_buf[0..avail_len].copy_from_slice(__input);
14904 Bytes::new(&payload_buf)
14905 } else {
14906 Bytes::new(__input)
14907 };
14908 let mut __struct = Self::default();
14909 __struct.time_usec = buf.get_u64_le();
14910 __struct.lat = buf.get_i32_le();
14911 __struct.lon = buf.get_i32_le();
14912 __struct.alt = buf.get_i32_le();
14913 __struct.relative_alt = buf.get_i32_le();
14914 __struct.vx = buf.get_f32_le();
14915 __struct.vy = buf.get_f32_le();
14916 __struct.vz = buf.get_f32_le();
14917 for v in &mut __struct.covariance {
14918 let val = buf.get_f32_le();
14919 *v = val;
14920 }
14921 let tmp = buf.get_u8();
14922 __struct.estimator_type =
14923 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
14924 enum_type: "MavEstimatorType",
14925 value: tmp as u32,
14926 })?;
14927 Ok(__struct)
14928 }
14929 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14930 let mut __tmp = BytesMut::new(bytes);
14931 #[allow(clippy::absurd_extreme_comparisons)]
14932 #[allow(unused_comparisons)]
14933 if __tmp.remaining() < Self::ENCODED_LEN {
14934 panic!(
14935 "buffer is too small (need {} bytes, but got {})",
14936 Self::ENCODED_LEN,
14937 __tmp.remaining(),
14938 )
14939 }
14940 __tmp.put_u64_le(self.time_usec);
14941 __tmp.put_i32_le(self.lat);
14942 __tmp.put_i32_le(self.lon);
14943 __tmp.put_i32_le(self.alt);
14944 __tmp.put_i32_le(self.relative_alt);
14945 __tmp.put_f32_le(self.vx);
14946 __tmp.put_f32_le(self.vy);
14947 __tmp.put_f32_le(self.vz);
14948 for val in &self.covariance {
14949 __tmp.put_f32_le(*val);
14950 }
14951 __tmp.put_u8(self.estimator_type as u8);
14952 if matches!(version, MavlinkVersion::V2) {
14953 let len = __tmp.len();
14954 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14955 } else {
14956 __tmp.len()
14957 }
14958 }
14959}
14960#[doc = "id: 32"]
14961#[doc = "The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention)."]
14962#[derive(Debug, Clone, PartialEq)]
14963#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14964#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14965pub struct LOCAL_POSITION_NED_DATA {
14966 #[doc = "Timestamp (time since system boot)."]
14967 pub time_boot_ms: u32,
14968 #[doc = "X Position"]
14969 pub x: f32,
14970 #[doc = "Y Position"]
14971 pub y: f32,
14972 #[doc = "Z Position"]
14973 pub z: f32,
14974 #[doc = "X Speed"]
14975 pub vx: f32,
14976 #[doc = "Y Speed"]
14977 pub vy: f32,
14978 #[doc = "Z Speed"]
14979 pub vz: f32,
14980}
14981impl LOCAL_POSITION_NED_DATA {
14982 pub const ENCODED_LEN: usize = 28usize;
14983 pub const DEFAULT: Self = Self {
14984 time_boot_ms: 0_u32,
14985 x: 0.0_f32,
14986 y: 0.0_f32,
14987 z: 0.0_f32,
14988 vx: 0.0_f32,
14989 vy: 0.0_f32,
14990 vz: 0.0_f32,
14991 };
14992 #[cfg(feature = "arbitrary")]
14993 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14994 use arbitrary::{Arbitrary, Unstructured};
14995 let mut buf = [0u8; 1024];
14996 rng.fill_bytes(&mut buf);
14997 let mut unstructured = Unstructured::new(&buf);
14998 Self::arbitrary(&mut unstructured).unwrap_or_default()
14999 }
15000}
15001impl Default for LOCAL_POSITION_NED_DATA {
15002 fn default() -> Self {
15003 Self::DEFAULT.clone()
15004 }
15005}
15006impl MessageData for LOCAL_POSITION_NED_DATA {
15007 type Message = MavMessage;
15008 const ID: u32 = 32u32;
15009 const NAME: &'static str = "LOCAL_POSITION_NED";
15010 const EXTRA_CRC: u8 = 185u8;
15011 const ENCODED_LEN: usize = 28usize;
15012 fn deser(
15013 _version: MavlinkVersion,
15014 __input: &[u8],
15015 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15016 let avail_len = __input.len();
15017 let mut payload_buf = [0; Self::ENCODED_LEN];
15018 let mut buf = if avail_len < Self::ENCODED_LEN {
15019 payload_buf[0..avail_len].copy_from_slice(__input);
15020 Bytes::new(&payload_buf)
15021 } else {
15022 Bytes::new(__input)
15023 };
15024 let mut __struct = Self::default();
15025 __struct.time_boot_ms = buf.get_u32_le();
15026 __struct.x = buf.get_f32_le();
15027 __struct.y = buf.get_f32_le();
15028 __struct.z = buf.get_f32_le();
15029 __struct.vx = buf.get_f32_le();
15030 __struct.vy = buf.get_f32_le();
15031 __struct.vz = buf.get_f32_le();
15032 Ok(__struct)
15033 }
15034 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15035 let mut __tmp = BytesMut::new(bytes);
15036 #[allow(clippy::absurd_extreme_comparisons)]
15037 #[allow(unused_comparisons)]
15038 if __tmp.remaining() < Self::ENCODED_LEN {
15039 panic!(
15040 "buffer is too small (need {} bytes, but got {})",
15041 Self::ENCODED_LEN,
15042 __tmp.remaining(),
15043 )
15044 }
15045 __tmp.put_u32_le(self.time_boot_ms);
15046 __tmp.put_f32_le(self.x);
15047 __tmp.put_f32_le(self.y);
15048 __tmp.put_f32_le(self.z);
15049 __tmp.put_f32_le(self.vx);
15050 __tmp.put_f32_le(self.vy);
15051 __tmp.put_f32_le(self.vz);
15052 if matches!(version, MavlinkVersion::V2) {
15053 let len = __tmp.len();
15054 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
15055 } else {
15056 __tmp.len()
15057 }
15058 }
15059}
15060#[doc = "id: 66"]
15061#[doc = "Request a data stream."]
15062#[derive(Debug, Clone, PartialEq)]
15063#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15064#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15065pub struct REQUEST_DATA_STREAM_DATA {
15066 #[doc = "The requested message rate"]
15067 pub req_message_rate: u16,
15068 #[doc = "The target requested to send the message stream."]
15069 pub target_system: u8,
15070 #[doc = "The target requested to send the message stream."]
15071 pub target_component: u8,
15072 #[doc = "The ID of the requested data stream"]
15073 pub req_stream_id: u8,
15074 #[doc = "1 to start sending, 0 to stop sending."]
15075 pub start_stop: u8,
15076}
15077impl REQUEST_DATA_STREAM_DATA {
15078 pub const ENCODED_LEN: usize = 6usize;
15079 pub const DEFAULT: Self = Self {
15080 req_message_rate: 0_u16,
15081 target_system: 0_u8,
15082 target_component: 0_u8,
15083 req_stream_id: 0_u8,
15084 start_stop: 0_u8,
15085 };
15086 #[cfg(feature = "arbitrary")]
15087 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15088 use arbitrary::{Arbitrary, Unstructured};
15089 let mut buf = [0u8; 1024];
15090 rng.fill_bytes(&mut buf);
15091 let mut unstructured = Unstructured::new(&buf);
15092 Self::arbitrary(&mut unstructured).unwrap_or_default()
15093 }
15094}
15095impl Default for REQUEST_DATA_STREAM_DATA {
15096 fn default() -> Self {
15097 Self::DEFAULT.clone()
15098 }
15099}
15100impl MessageData for REQUEST_DATA_STREAM_DATA {
15101 type Message = MavMessage;
15102 const ID: u32 = 66u32;
15103 const NAME: &'static str = "REQUEST_DATA_STREAM";
15104 const EXTRA_CRC: u8 = 148u8;
15105 const ENCODED_LEN: usize = 6usize;
15106 fn deser(
15107 _version: MavlinkVersion,
15108 __input: &[u8],
15109 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15110 let avail_len = __input.len();
15111 let mut payload_buf = [0; Self::ENCODED_LEN];
15112 let mut buf = if avail_len < Self::ENCODED_LEN {
15113 payload_buf[0..avail_len].copy_from_slice(__input);
15114 Bytes::new(&payload_buf)
15115 } else {
15116 Bytes::new(__input)
15117 };
15118 let mut __struct = Self::default();
15119 __struct.req_message_rate = buf.get_u16_le();
15120 __struct.target_system = buf.get_u8();
15121 __struct.target_component = buf.get_u8();
15122 __struct.req_stream_id = buf.get_u8();
15123 __struct.start_stop = buf.get_u8();
15124 Ok(__struct)
15125 }
15126 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15127 let mut __tmp = BytesMut::new(bytes);
15128 #[allow(clippy::absurd_extreme_comparisons)]
15129 #[allow(unused_comparisons)]
15130 if __tmp.remaining() < Self::ENCODED_LEN {
15131 panic!(
15132 "buffer is too small (need {} bytes, but got {})",
15133 Self::ENCODED_LEN,
15134 __tmp.remaining(),
15135 )
15136 }
15137 __tmp.put_u16_le(self.req_message_rate);
15138 __tmp.put_u8(self.target_system);
15139 __tmp.put_u8(self.target_component);
15140 __tmp.put_u8(self.req_stream_id);
15141 __tmp.put_u8(self.start_stop);
15142 if matches!(version, MavlinkVersion::V2) {
15143 let len = __tmp.len();
15144 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
15145 } else {
15146 __tmp.len()
15147 }
15148 }
15149}
15150#[doc = "id: 134"]
15151#[doc = "Terrain data sent from GCS. The lat/lon and grid_spacing must be the same as a lat/lon from a TERRAIN_REQUEST. See terrain protocol docs: <https://mavlink.io/en/services/terrain.html>."]
15152#[derive(Debug, Clone, PartialEq)]
15153#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15154#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15155pub struct TERRAIN_DATA_DATA {
15156 #[doc = "Latitude of SW corner of first grid"]
15157 pub lat: i32,
15158 #[doc = "Longitude of SW corner of first grid"]
15159 pub lon: i32,
15160 #[doc = "Grid spacing"]
15161 pub grid_spacing: u16,
15162 #[doc = "Terrain data MSL"]
15163 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
15164 pub data: [i16; 16],
15165 #[doc = "bit within the terrain request mask"]
15166 pub gridbit: u8,
15167}
15168impl TERRAIN_DATA_DATA {
15169 pub const ENCODED_LEN: usize = 43usize;
15170 pub const DEFAULT: Self = Self {
15171 lat: 0_i32,
15172 lon: 0_i32,
15173 grid_spacing: 0_u16,
15174 data: [0_i16; 16usize],
15175 gridbit: 0_u8,
15176 };
15177 #[cfg(feature = "arbitrary")]
15178 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15179 use arbitrary::{Arbitrary, Unstructured};
15180 let mut buf = [0u8; 1024];
15181 rng.fill_bytes(&mut buf);
15182 let mut unstructured = Unstructured::new(&buf);
15183 Self::arbitrary(&mut unstructured).unwrap_or_default()
15184 }
15185}
15186impl Default for TERRAIN_DATA_DATA {
15187 fn default() -> Self {
15188 Self::DEFAULT.clone()
15189 }
15190}
15191impl MessageData for TERRAIN_DATA_DATA {
15192 type Message = MavMessage;
15193 const ID: u32 = 134u32;
15194 const NAME: &'static str = "TERRAIN_DATA";
15195 const EXTRA_CRC: u8 = 229u8;
15196 const ENCODED_LEN: usize = 43usize;
15197 fn deser(
15198 _version: MavlinkVersion,
15199 __input: &[u8],
15200 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15201 let avail_len = __input.len();
15202 let mut payload_buf = [0; Self::ENCODED_LEN];
15203 let mut buf = if avail_len < Self::ENCODED_LEN {
15204 payload_buf[0..avail_len].copy_from_slice(__input);
15205 Bytes::new(&payload_buf)
15206 } else {
15207 Bytes::new(__input)
15208 };
15209 let mut __struct = Self::default();
15210 __struct.lat = buf.get_i32_le();
15211 __struct.lon = buf.get_i32_le();
15212 __struct.grid_spacing = buf.get_u16_le();
15213 for v in &mut __struct.data {
15214 let val = buf.get_i16_le();
15215 *v = val;
15216 }
15217 __struct.gridbit = buf.get_u8();
15218 Ok(__struct)
15219 }
15220 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15221 let mut __tmp = BytesMut::new(bytes);
15222 #[allow(clippy::absurd_extreme_comparisons)]
15223 #[allow(unused_comparisons)]
15224 if __tmp.remaining() < Self::ENCODED_LEN {
15225 panic!(
15226 "buffer is too small (need {} bytes, but got {})",
15227 Self::ENCODED_LEN,
15228 __tmp.remaining(),
15229 )
15230 }
15231 __tmp.put_i32_le(self.lat);
15232 __tmp.put_i32_le(self.lon);
15233 __tmp.put_u16_le(self.grid_spacing);
15234 for val in &self.data {
15235 __tmp.put_i16_le(*val);
15236 }
15237 __tmp.put_u8(self.gridbit);
15238 if matches!(version, MavlinkVersion::V2) {
15239 let len = __tmp.len();
15240 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
15241 } else {
15242 __tmp.len()
15243 }
15244 }
15245}
15246#[doc = "id: 271"]
15247#[doc = "Information about the field of view of a camera. Can be requested with a MAV_CMD_REQUEST_MESSAGE command."]
15248#[derive(Debug, Clone, PartialEq)]
15249#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15250#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15251pub struct CAMERA_FOV_STATUS_DATA {
15252 #[doc = "Timestamp (time since system boot)."]
15253 pub time_boot_ms: u32,
15254 #[doc = "Latitude of camera (INT32_MAX if unknown)."]
15255 pub lat_camera: i32,
15256 #[doc = "Longitude of camera (INT32_MAX if unknown)."]
15257 pub lon_camera: i32,
15258 #[doc = "Altitude (MSL) of camera (INT32_MAX if unknown)."]
15259 pub alt_camera: i32,
15260 #[doc = "Latitude of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon)."]
15261 pub lat_image: i32,
15262 #[doc = "Longitude of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon)."]
15263 pub lon_image: i32,
15264 #[doc = "Altitude (MSL) of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon)."]
15265 pub alt_image: i32,
15266 #[doc = "Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)"]
15267 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
15268 pub q: [f32; 4],
15269 #[doc = "Horizontal field of view (NaN if unknown)."]
15270 pub hfov: f32,
15271 #[doc = "Vertical field of view (NaN if unknown)."]
15272 pub vfov: f32,
15273 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
15274 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
15275 pub camera_device_id: u8,
15276}
15277impl CAMERA_FOV_STATUS_DATA {
15278 pub const ENCODED_LEN: usize = 53usize;
15279 pub const DEFAULT: Self = Self {
15280 time_boot_ms: 0_u32,
15281 lat_camera: 0_i32,
15282 lon_camera: 0_i32,
15283 alt_camera: 0_i32,
15284 lat_image: 0_i32,
15285 lon_image: 0_i32,
15286 alt_image: 0_i32,
15287 q: [0.0_f32; 4usize],
15288 hfov: 0.0_f32,
15289 vfov: 0.0_f32,
15290 camera_device_id: 0_u8,
15291 };
15292 #[cfg(feature = "arbitrary")]
15293 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15294 use arbitrary::{Arbitrary, Unstructured};
15295 let mut buf = [0u8; 1024];
15296 rng.fill_bytes(&mut buf);
15297 let mut unstructured = Unstructured::new(&buf);
15298 Self::arbitrary(&mut unstructured).unwrap_or_default()
15299 }
15300}
15301impl Default for CAMERA_FOV_STATUS_DATA {
15302 fn default() -> Self {
15303 Self::DEFAULT.clone()
15304 }
15305}
15306impl MessageData for CAMERA_FOV_STATUS_DATA {
15307 type Message = MavMessage;
15308 const ID: u32 = 271u32;
15309 const NAME: &'static str = "CAMERA_FOV_STATUS";
15310 const EXTRA_CRC: u8 = 22u8;
15311 const ENCODED_LEN: usize = 53usize;
15312 fn deser(
15313 _version: MavlinkVersion,
15314 __input: &[u8],
15315 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15316 let avail_len = __input.len();
15317 let mut payload_buf = [0; Self::ENCODED_LEN];
15318 let mut buf = if avail_len < Self::ENCODED_LEN {
15319 payload_buf[0..avail_len].copy_from_slice(__input);
15320 Bytes::new(&payload_buf)
15321 } else {
15322 Bytes::new(__input)
15323 };
15324 let mut __struct = Self::default();
15325 __struct.time_boot_ms = buf.get_u32_le();
15326 __struct.lat_camera = buf.get_i32_le();
15327 __struct.lon_camera = buf.get_i32_le();
15328 __struct.alt_camera = buf.get_i32_le();
15329 __struct.lat_image = buf.get_i32_le();
15330 __struct.lon_image = buf.get_i32_le();
15331 __struct.alt_image = buf.get_i32_le();
15332 for v in &mut __struct.q {
15333 let val = buf.get_f32_le();
15334 *v = val;
15335 }
15336 __struct.hfov = buf.get_f32_le();
15337 __struct.vfov = buf.get_f32_le();
15338 __struct.camera_device_id = buf.get_u8();
15339 Ok(__struct)
15340 }
15341 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15342 let mut __tmp = BytesMut::new(bytes);
15343 #[allow(clippy::absurd_extreme_comparisons)]
15344 #[allow(unused_comparisons)]
15345 if __tmp.remaining() < Self::ENCODED_LEN {
15346 panic!(
15347 "buffer is too small (need {} bytes, but got {})",
15348 Self::ENCODED_LEN,
15349 __tmp.remaining(),
15350 )
15351 }
15352 __tmp.put_u32_le(self.time_boot_ms);
15353 __tmp.put_i32_le(self.lat_camera);
15354 __tmp.put_i32_le(self.lon_camera);
15355 __tmp.put_i32_le(self.alt_camera);
15356 __tmp.put_i32_le(self.lat_image);
15357 __tmp.put_i32_le(self.lon_image);
15358 __tmp.put_i32_le(self.alt_image);
15359 for val in &self.q {
15360 __tmp.put_f32_le(*val);
15361 }
15362 __tmp.put_f32_le(self.hfov);
15363 __tmp.put_f32_le(self.vfov);
15364 __tmp.put_u8(self.camera_device_id);
15365 if matches!(version, MavlinkVersion::V2) {
15366 let len = __tmp.len();
15367 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
15368 } else {
15369 __tmp.len()
15370 }
15371 }
15372}
15373#[doc = "id: 135"]
15374#[doc = "Request that the vehicle report terrain height at the given location (expected response is a TERRAIN_REPORT). Used by GCS to check if vehicle has all terrain data needed for a mission."]
15375#[derive(Debug, Clone, PartialEq)]
15376#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15377#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15378pub struct TERRAIN_CHECK_DATA {
15379 #[doc = "Latitude"]
15380 pub lat: i32,
15381 #[doc = "Longitude"]
15382 pub lon: i32,
15383}
15384impl TERRAIN_CHECK_DATA {
15385 pub const ENCODED_LEN: usize = 8usize;
15386 pub const DEFAULT: Self = Self {
15387 lat: 0_i32,
15388 lon: 0_i32,
15389 };
15390 #[cfg(feature = "arbitrary")]
15391 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15392 use arbitrary::{Arbitrary, Unstructured};
15393 let mut buf = [0u8; 1024];
15394 rng.fill_bytes(&mut buf);
15395 let mut unstructured = Unstructured::new(&buf);
15396 Self::arbitrary(&mut unstructured).unwrap_or_default()
15397 }
15398}
15399impl Default for TERRAIN_CHECK_DATA {
15400 fn default() -> Self {
15401 Self::DEFAULT.clone()
15402 }
15403}
15404impl MessageData for TERRAIN_CHECK_DATA {
15405 type Message = MavMessage;
15406 const ID: u32 = 135u32;
15407 const NAME: &'static str = "TERRAIN_CHECK";
15408 const EXTRA_CRC: u8 = 203u8;
15409 const ENCODED_LEN: usize = 8usize;
15410 fn deser(
15411 _version: MavlinkVersion,
15412 __input: &[u8],
15413 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15414 let avail_len = __input.len();
15415 let mut payload_buf = [0; Self::ENCODED_LEN];
15416 let mut buf = if avail_len < Self::ENCODED_LEN {
15417 payload_buf[0..avail_len].copy_from_slice(__input);
15418 Bytes::new(&payload_buf)
15419 } else {
15420 Bytes::new(__input)
15421 };
15422 let mut __struct = Self::default();
15423 __struct.lat = buf.get_i32_le();
15424 __struct.lon = buf.get_i32_le();
15425 Ok(__struct)
15426 }
15427 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15428 let mut __tmp = BytesMut::new(bytes);
15429 #[allow(clippy::absurd_extreme_comparisons)]
15430 #[allow(unused_comparisons)]
15431 if __tmp.remaining() < Self::ENCODED_LEN {
15432 panic!(
15433 "buffer is too small (need {} bytes, but got {})",
15434 Self::ENCODED_LEN,
15435 __tmp.remaining(),
15436 )
15437 }
15438 __tmp.put_i32_le(self.lat);
15439 __tmp.put_i32_le(self.lon);
15440 if matches!(version, MavlinkVersion::V2) {
15441 let len = __tmp.len();
15442 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
15443 } else {
15444 __tmp.len()
15445 }
15446 }
15447}
15448#[doc = "id: 242"]
15449#[doc = "Contains the home position. \tThe home position is the default position that the system will return to and land on. \tThe position must be set automatically by the system during the takeoff, and may also be explicitly set using MAV_CMD_DO_SET_HOME. \tThe global and local positions encode the position in the respective coordinate frames, while the q parameter encodes the orientation of the surface. \tUnder normal conditions it describes the heading and terrain slope, which can be used by the aircraft to adjust the approach. \tThe approach 3D vector describes the point to which the system should fly in normal flight mode and then perform a landing sequence along the vector. Note: this message can be requested by sending the MAV_CMD_REQUEST_MESSAGE with param1=242 (or the deprecated MAV_CMD_GET_HOME_POSITION command)."]
15450#[derive(Debug, Clone, PartialEq)]
15451#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15452#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15453pub struct HOME_POSITION_DATA {
15454 #[doc = "Latitude (WGS84)"]
15455 pub latitude: i32,
15456 #[doc = "Longitude (WGS84)"]
15457 pub longitude: i32,
15458 #[doc = "Altitude (MSL). Positive for up."]
15459 pub altitude: i32,
15460 #[doc = "Local X position of this position in the local coordinate frame (NED)"]
15461 pub x: f32,
15462 #[doc = "Local Y position of this position in the local coordinate frame (NED)"]
15463 pub y: f32,
15464 #[doc = "Local Z position of this position in the local coordinate frame (NED: positive \"down\")"]
15465 pub z: f32,
15466 #[doc = "Quaternion indicating world-to-surface-normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground. All fields should be set to NaN if an accurate quaternion for both heading and surface slope cannot be supplied."]
15467 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
15468 pub q: [f32; 4],
15469 #[doc = "Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone."]
15470 pub approach_x: f32,
15471 #[doc = "Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone."]
15472 pub approach_y: f32,
15473 #[doc = "Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone."]
15474 pub approach_z: f32,
15475 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
15476 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
15477 pub time_usec: u64,
15478}
15479impl HOME_POSITION_DATA {
15480 pub const ENCODED_LEN: usize = 60usize;
15481 pub const DEFAULT: Self = Self {
15482 latitude: 0_i32,
15483 longitude: 0_i32,
15484 altitude: 0_i32,
15485 x: 0.0_f32,
15486 y: 0.0_f32,
15487 z: 0.0_f32,
15488 q: [0.0_f32; 4usize],
15489 approach_x: 0.0_f32,
15490 approach_y: 0.0_f32,
15491 approach_z: 0.0_f32,
15492 time_usec: 0_u64,
15493 };
15494 #[cfg(feature = "arbitrary")]
15495 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15496 use arbitrary::{Arbitrary, Unstructured};
15497 let mut buf = [0u8; 1024];
15498 rng.fill_bytes(&mut buf);
15499 let mut unstructured = Unstructured::new(&buf);
15500 Self::arbitrary(&mut unstructured).unwrap_or_default()
15501 }
15502}
15503impl Default for HOME_POSITION_DATA {
15504 fn default() -> Self {
15505 Self::DEFAULT.clone()
15506 }
15507}
15508impl MessageData for HOME_POSITION_DATA {
15509 type Message = MavMessage;
15510 const ID: u32 = 242u32;
15511 const NAME: &'static str = "HOME_POSITION";
15512 const EXTRA_CRC: u8 = 104u8;
15513 const ENCODED_LEN: usize = 60usize;
15514 fn deser(
15515 _version: MavlinkVersion,
15516 __input: &[u8],
15517 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15518 let avail_len = __input.len();
15519 let mut payload_buf = [0; Self::ENCODED_LEN];
15520 let mut buf = if avail_len < Self::ENCODED_LEN {
15521 payload_buf[0..avail_len].copy_from_slice(__input);
15522 Bytes::new(&payload_buf)
15523 } else {
15524 Bytes::new(__input)
15525 };
15526 let mut __struct = Self::default();
15527 __struct.latitude = buf.get_i32_le();
15528 __struct.longitude = buf.get_i32_le();
15529 __struct.altitude = buf.get_i32_le();
15530 __struct.x = buf.get_f32_le();
15531 __struct.y = buf.get_f32_le();
15532 __struct.z = buf.get_f32_le();
15533 for v in &mut __struct.q {
15534 let val = buf.get_f32_le();
15535 *v = val;
15536 }
15537 __struct.approach_x = buf.get_f32_le();
15538 __struct.approach_y = buf.get_f32_le();
15539 __struct.approach_z = buf.get_f32_le();
15540 __struct.time_usec = buf.get_u64_le();
15541 Ok(__struct)
15542 }
15543 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15544 let mut __tmp = BytesMut::new(bytes);
15545 #[allow(clippy::absurd_extreme_comparisons)]
15546 #[allow(unused_comparisons)]
15547 if __tmp.remaining() < Self::ENCODED_LEN {
15548 panic!(
15549 "buffer is too small (need {} bytes, but got {})",
15550 Self::ENCODED_LEN,
15551 __tmp.remaining(),
15552 )
15553 }
15554 __tmp.put_i32_le(self.latitude);
15555 __tmp.put_i32_le(self.longitude);
15556 __tmp.put_i32_le(self.altitude);
15557 __tmp.put_f32_le(self.x);
15558 __tmp.put_f32_le(self.y);
15559 __tmp.put_f32_le(self.z);
15560 for val in &self.q {
15561 __tmp.put_f32_le(*val);
15562 }
15563 __tmp.put_f32_le(self.approach_x);
15564 __tmp.put_f32_le(self.approach_y);
15565 __tmp.put_f32_le(self.approach_z);
15566 __tmp.put_u64_le(self.time_usec);
15567 if matches!(version, MavlinkVersion::V2) {
15568 let len = __tmp.len();
15569 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
15570 } else {
15571 __tmp.len()
15572 }
15573 }
15574}
15575#[doc = "id: 107"]
15576#[doc = "The IMU readings in SI units in NED body frame."]
15577#[derive(Debug, Clone, PartialEq)]
15578#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15579#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15580pub struct HIL_SENSOR_DATA {
15581 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
15582 pub time_usec: u64,
15583 #[doc = "X acceleration"]
15584 pub xacc: f32,
15585 #[doc = "Y acceleration"]
15586 pub yacc: f32,
15587 #[doc = "Z acceleration"]
15588 pub zacc: f32,
15589 #[doc = "Angular speed around X axis in body frame"]
15590 pub xgyro: f32,
15591 #[doc = "Angular speed around Y axis in body frame"]
15592 pub ygyro: f32,
15593 #[doc = "Angular speed around Z axis in body frame"]
15594 pub zgyro: f32,
15595 #[doc = "X Magnetic field"]
15596 pub xmag: f32,
15597 #[doc = "Y Magnetic field"]
15598 pub ymag: f32,
15599 #[doc = "Z Magnetic field"]
15600 pub zmag: f32,
15601 #[doc = "Absolute pressure"]
15602 pub abs_pressure: f32,
15603 #[doc = "Differential pressure (airspeed)"]
15604 pub diff_pressure: f32,
15605 #[doc = "Altitude calculated from pressure"]
15606 pub pressure_alt: f32,
15607 #[doc = "Temperature"]
15608 pub temperature: f32,
15609 #[doc = "Bitmap for fields that have updated since last message"]
15610 pub fields_updated: HilSensorUpdatedFlags,
15611 #[doc = "Sensor ID (zero indexed). Used for multiple sensor inputs"]
15612 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
15613 pub id: u8,
15614}
15615impl HIL_SENSOR_DATA {
15616 pub const ENCODED_LEN: usize = 65usize;
15617 pub const DEFAULT: Self = Self {
15618 time_usec: 0_u64,
15619 xacc: 0.0_f32,
15620 yacc: 0.0_f32,
15621 zacc: 0.0_f32,
15622 xgyro: 0.0_f32,
15623 ygyro: 0.0_f32,
15624 zgyro: 0.0_f32,
15625 xmag: 0.0_f32,
15626 ymag: 0.0_f32,
15627 zmag: 0.0_f32,
15628 abs_pressure: 0.0_f32,
15629 diff_pressure: 0.0_f32,
15630 pressure_alt: 0.0_f32,
15631 temperature: 0.0_f32,
15632 fields_updated: HilSensorUpdatedFlags::DEFAULT,
15633 id: 0_u8,
15634 };
15635 #[cfg(feature = "arbitrary")]
15636 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15637 use arbitrary::{Arbitrary, Unstructured};
15638 let mut buf = [0u8; 1024];
15639 rng.fill_bytes(&mut buf);
15640 let mut unstructured = Unstructured::new(&buf);
15641 Self::arbitrary(&mut unstructured).unwrap_or_default()
15642 }
15643}
15644impl Default for HIL_SENSOR_DATA {
15645 fn default() -> Self {
15646 Self::DEFAULT.clone()
15647 }
15648}
15649impl MessageData for HIL_SENSOR_DATA {
15650 type Message = MavMessage;
15651 const ID: u32 = 107u32;
15652 const NAME: &'static str = "HIL_SENSOR";
15653 const EXTRA_CRC: u8 = 108u8;
15654 const ENCODED_LEN: usize = 65usize;
15655 fn deser(
15656 _version: MavlinkVersion,
15657 __input: &[u8],
15658 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15659 let avail_len = __input.len();
15660 let mut payload_buf = [0; Self::ENCODED_LEN];
15661 let mut buf = if avail_len < Self::ENCODED_LEN {
15662 payload_buf[0..avail_len].copy_from_slice(__input);
15663 Bytes::new(&payload_buf)
15664 } else {
15665 Bytes::new(__input)
15666 };
15667 let mut __struct = Self::default();
15668 __struct.time_usec = buf.get_u64_le();
15669 __struct.xacc = buf.get_f32_le();
15670 __struct.yacc = buf.get_f32_le();
15671 __struct.zacc = buf.get_f32_le();
15672 __struct.xgyro = buf.get_f32_le();
15673 __struct.ygyro = buf.get_f32_le();
15674 __struct.zgyro = buf.get_f32_le();
15675 __struct.xmag = buf.get_f32_le();
15676 __struct.ymag = buf.get_f32_le();
15677 __struct.zmag = buf.get_f32_le();
15678 __struct.abs_pressure = buf.get_f32_le();
15679 __struct.diff_pressure = buf.get_f32_le();
15680 __struct.pressure_alt = buf.get_f32_le();
15681 __struct.temperature = buf.get_f32_le();
15682 let tmp = buf.get_u32_le();
15683 __struct.fields_updated = HilSensorUpdatedFlags::from_bits(
15684 tmp & HilSensorUpdatedFlags::all().bits(),
15685 )
15686 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
15687 flag_type: "HilSensorUpdatedFlags",
15688 value: tmp as u32,
15689 })?;
15690 __struct.id = buf.get_u8();
15691 Ok(__struct)
15692 }
15693 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15694 let mut __tmp = BytesMut::new(bytes);
15695 #[allow(clippy::absurd_extreme_comparisons)]
15696 #[allow(unused_comparisons)]
15697 if __tmp.remaining() < Self::ENCODED_LEN {
15698 panic!(
15699 "buffer is too small (need {} bytes, but got {})",
15700 Self::ENCODED_LEN,
15701 __tmp.remaining(),
15702 )
15703 }
15704 __tmp.put_u64_le(self.time_usec);
15705 __tmp.put_f32_le(self.xacc);
15706 __tmp.put_f32_le(self.yacc);
15707 __tmp.put_f32_le(self.zacc);
15708 __tmp.put_f32_le(self.xgyro);
15709 __tmp.put_f32_le(self.ygyro);
15710 __tmp.put_f32_le(self.zgyro);
15711 __tmp.put_f32_le(self.xmag);
15712 __tmp.put_f32_le(self.ymag);
15713 __tmp.put_f32_le(self.zmag);
15714 __tmp.put_f32_le(self.abs_pressure);
15715 __tmp.put_f32_le(self.diff_pressure);
15716 __tmp.put_f32_le(self.pressure_alt);
15717 __tmp.put_f32_le(self.temperature);
15718 __tmp.put_u32_le(self.fields_updated.bits());
15719 __tmp.put_u8(self.id);
15720 if matches!(version, MavlinkVersion::V2) {
15721 let len = __tmp.len();
15722 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
15723 } else {
15724 __tmp.len()
15725 }
15726 }
15727}
15728#[doc = "id: 125"]
15729#[doc = "Power supply status."]
15730#[derive(Debug, Clone, PartialEq)]
15731#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15732#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15733pub struct POWER_STATUS_DATA {
15734 #[doc = "5V rail voltage."]
15735 pub Vcc: u16,
15736 #[doc = "Servo rail voltage."]
15737 pub Vservo: u16,
15738 #[doc = "Bitmap of power supply status flags."]
15739 pub flags: MavPowerStatus,
15740}
15741impl POWER_STATUS_DATA {
15742 pub const ENCODED_LEN: usize = 6usize;
15743 pub const DEFAULT: Self = Self {
15744 Vcc: 0_u16,
15745 Vservo: 0_u16,
15746 flags: MavPowerStatus::DEFAULT,
15747 };
15748 #[cfg(feature = "arbitrary")]
15749 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15750 use arbitrary::{Arbitrary, Unstructured};
15751 let mut buf = [0u8; 1024];
15752 rng.fill_bytes(&mut buf);
15753 let mut unstructured = Unstructured::new(&buf);
15754 Self::arbitrary(&mut unstructured).unwrap_or_default()
15755 }
15756}
15757impl Default for POWER_STATUS_DATA {
15758 fn default() -> Self {
15759 Self::DEFAULT.clone()
15760 }
15761}
15762impl MessageData for POWER_STATUS_DATA {
15763 type Message = MavMessage;
15764 const ID: u32 = 125u32;
15765 const NAME: &'static str = "POWER_STATUS";
15766 const EXTRA_CRC: u8 = 203u8;
15767 const ENCODED_LEN: usize = 6usize;
15768 fn deser(
15769 _version: MavlinkVersion,
15770 __input: &[u8],
15771 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15772 let avail_len = __input.len();
15773 let mut payload_buf = [0; Self::ENCODED_LEN];
15774 let mut buf = if avail_len < Self::ENCODED_LEN {
15775 payload_buf[0..avail_len].copy_from_slice(__input);
15776 Bytes::new(&payload_buf)
15777 } else {
15778 Bytes::new(__input)
15779 };
15780 let mut __struct = Self::default();
15781 __struct.Vcc = buf.get_u16_le();
15782 __struct.Vservo = buf.get_u16_le();
15783 let tmp = buf.get_u16_le();
15784 __struct.flags = MavPowerStatus::from_bits(tmp & MavPowerStatus::all().bits()).ok_or(
15785 ::mavlink_core::error::ParserError::InvalidFlag {
15786 flag_type: "MavPowerStatus",
15787 value: tmp as u32,
15788 },
15789 )?;
15790 Ok(__struct)
15791 }
15792 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15793 let mut __tmp = BytesMut::new(bytes);
15794 #[allow(clippy::absurd_extreme_comparisons)]
15795 #[allow(unused_comparisons)]
15796 if __tmp.remaining() < Self::ENCODED_LEN {
15797 panic!(
15798 "buffer is too small (need {} bytes, but got {})",
15799 Self::ENCODED_LEN,
15800 __tmp.remaining(),
15801 )
15802 }
15803 __tmp.put_u16_le(self.Vcc);
15804 __tmp.put_u16_le(self.Vservo);
15805 __tmp.put_u16_le(self.flags.bits());
15806 if matches!(version, MavlinkVersion::V2) {
15807 let len = __tmp.len();
15808 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
15809 } else {
15810 __tmp.len()
15811 }
15812 }
15813}
15814#[doc = "id: 93"]
15815#[doc = "Sent from autopilot to simulation. Hardware in the loop control outputs. Alternative to HIL_CONTROLS."]
15816#[derive(Debug, Clone, PartialEq)]
15817#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15818#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15819pub struct HIL_ACTUATOR_CONTROLS_DATA {
15820 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
15821 pub time_usec: u64,
15822 #[doc = "Flags bitmask."]
15823 pub flags: HilActuatorControlsFlags,
15824 #[doc = "Control outputs -1 .. 1. Channel assignment depends on the simulated hardware."]
15825 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
15826 pub controls: [f32; 16],
15827 #[doc = "System mode. Includes arming state."]
15828 pub mode: MavModeFlag,
15829}
15830impl HIL_ACTUATOR_CONTROLS_DATA {
15831 pub const ENCODED_LEN: usize = 81usize;
15832 pub const DEFAULT: Self = Self {
15833 time_usec: 0_u64,
15834 flags: HilActuatorControlsFlags::DEFAULT,
15835 controls: [0.0_f32; 16usize],
15836 mode: MavModeFlag::DEFAULT,
15837 };
15838 #[cfg(feature = "arbitrary")]
15839 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15840 use arbitrary::{Arbitrary, Unstructured};
15841 let mut buf = [0u8; 1024];
15842 rng.fill_bytes(&mut buf);
15843 let mut unstructured = Unstructured::new(&buf);
15844 Self::arbitrary(&mut unstructured).unwrap_or_default()
15845 }
15846}
15847impl Default for HIL_ACTUATOR_CONTROLS_DATA {
15848 fn default() -> Self {
15849 Self::DEFAULT.clone()
15850 }
15851}
15852impl MessageData for HIL_ACTUATOR_CONTROLS_DATA {
15853 type Message = MavMessage;
15854 const ID: u32 = 93u32;
15855 const NAME: &'static str = "HIL_ACTUATOR_CONTROLS";
15856 const EXTRA_CRC: u8 = 47u8;
15857 const ENCODED_LEN: usize = 81usize;
15858 fn deser(
15859 _version: MavlinkVersion,
15860 __input: &[u8],
15861 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15862 let avail_len = __input.len();
15863 let mut payload_buf = [0; Self::ENCODED_LEN];
15864 let mut buf = if avail_len < Self::ENCODED_LEN {
15865 payload_buf[0..avail_len].copy_from_slice(__input);
15866 Bytes::new(&payload_buf)
15867 } else {
15868 Bytes::new(__input)
15869 };
15870 let mut __struct = Self::default();
15871 __struct.time_usec = buf.get_u64_le();
15872 let tmp = buf.get_u64_le();
15873 __struct.flags =
15874 HilActuatorControlsFlags::from_bits(tmp & HilActuatorControlsFlags::all().bits())
15875 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
15876 flag_type: "HilActuatorControlsFlags",
15877 value: tmp as u32,
15878 })?;
15879 for v in &mut __struct.controls {
15880 let val = buf.get_f32_le();
15881 *v = val;
15882 }
15883 let tmp = buf.get_u8();
15884 __struct.mode = MavModeFlag::from_bits(tmp & MavModeFlag::all().bits()).ok_or(
15885 ::mavlink_core::error::ParserError::InvalidFlag {
15886 flag_type: "MavModeFlag",
15887 value: tmp as u32,
15888 },
15889 )?;
15890 Ok(__struct)
15891 }
15892 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15893 let mut __tmp = BytesMut::new(bytes);
15894 #[allow(clippy::absurd_extreme_comparisons)]
15895 #[allow(unused_comparisons)]
15896 if __tmp.remaining() < Self::ENCODED_LEN {
15897 panic!(
15898 "buffer is too small (need {} bytes, but got {})",
15899 Self::ENCODED_LEN,
15900 __tmp.remaining(),
15901 )
15902 }
15903 __tmp.put_u64_le(self.time_usec);
15904 __tmp.put_u64_le(self.flags.bits());
15905 for val in &self.controls {
15906 __tmp.put_f32_le(*val);
15907 }
15908 __tmp.put_u8(self.mode.bits());
15909 if matches!(version, MavlinkVersion::V2) {
15910 let len = __tmp.len();
15911 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
15912 } else {
15913 __tmp.len()
15914 }
15915 }
15916}
15917#[doc = "id: 33"]
15918#[doc = "The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up). It is designed as scaled integer message since the resolution of float is not sufficient."]
15919#[derive(Debug, Clone, PartialEq)]
15920#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15921#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15922pub struct GLOBAL_POSITION_INT_DATA {
15923 #[doc = "Timestamp (time since system boot)."]
15924 pub time_boot_ms: u32,
15925 #[doc = "Latitude, expressed"]
15926 pub lat: i32,
15927 #[doc = "Longitude, expressed"]
15928 pub lon: i32,
15929 #[doc = "Altitude (MSL). Note that virtually all GPS modules provide both WGS84 and MSL."]
15930 pub alt: i32,
15931 #[doc = "Altitude above home"]
15932 pub relative_alt: i32,
15933 #[doc = "Ground X Speed (Latitude, positive north)"]
15934 pub vx: i16,
15935 #[doc = "Ground Y Speed (Longitude, positive east)"]
15936 pub vy: i16,
15937 #[doc = "Ground Z Speed (Altitude, positive down)"]
15938 pub vz: i16,
15939 #[doc = "Vehicle heading (yaw angle), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX"]
15940 pub hdg: u16,
15941}
15942impl GLOBAL_POSITION_INT_DATA {
15943 pub const ENCODED_LEN: usize = 28usize;
15944 pub const DEFAULT: Self = Self {
15945 time_boot_ms: 0_u32,
15946 lat: 0_i32,
15947 lon: 0_i32,
15948 alt: 0_i32,
15949 relative_alt: 0_i32,
15950 vx: 0_i16,
15951 vy: 0_i16,
15952 vz: 0_i16,
15953 hdg: 0_u16,
15954 };
15955 #[cfg(feature = "arbitrary")]
15956 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15957 use arbitrary::{Arbitrary, Unstructured};
15958 let mut buf = [0u8; 1024];
15959 rng.fill_bytes(&mut buf);
15960 let mut unstructured = Unstructured::new(&buf);
15961 Self::arbitrary(&mut unstructured).unwrap_or_default()
15962 }
15963}
15964impl Default for GLOBAL_POSITION_INT_DATA {
15965 fn default() -> Self {
15966 Self::DEFAULT.clone()
15967 }
15968}
15969impl MessageData for GLOBAL_POSITION_INT_DATA {
15970 type Message = MavMessage;
15971 const ID: u32 = 33u32;
15972 const NAME: &'static str = "GLOBAL_POSITION_INT";
15973 const EXTRA_CRC: u8 = 104u8;
15974 const ENCODED_LEN: usize = 28usize;
15975 fn deser(
15976 _version: MavlinkVersion,
15977 __input: &[u8],
15978 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15979 let avail_len = __input.len();
15980 let mut payload_buf = [0; Self::ENCODED_LEN];
15981 let mut buf = if avail_len < Self::ENCODED_LEN {
15982 payload_buf[0..avail_len].copy_from_slice(__input);
15983 Bytes::new(&payload_buf)
15984 } else {
15985 Bytes::new(__input)
15986 };
15987 let mut __struct = Self::default();
15988 __struct.time_boot_ms = buf.get_u32_le();
15989 __struct.lat = buf.get_i32_le();
15990 __struct.lon = buf.get_i32_le();
15991 __struct.alt = buf.get_i32_le();
15992 __struct.relative_alt = buf.get_i32_le();
15993 __struct.vx = buf.get_i16_le();
15994 __struct.vy = buf.get_i16_le();
15995 __struct.vz = buf.get_i16_le();
15996 __struct.hdg = buf.get_u16_le();
15997 Ok(__struct)
15998 }
15999 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16000 let mut __tmp = BytesMut::new(bytes);
16001 #[allow(clippy::absurd_extreme_comparisons)]
16002 #[allow(unused_comparisons)]
16003 if __tmp.remaining() < Self::ENCODED_LEN {
16004 panic!(
16005 "buffer is too small (need {} bytes, but got {})",
16006 Self::ENCODED_LEN,
16007 __tmp.remaining(),
16008 )
16009 }
16010 __tmp.put_u32_le(self.time_boot_ms);
16011 __tmp.put_i32_le(self.lat);
16012 __tmp.put_i32_le(self.lon);
16013 __tmp.put_i32_le(self.alt);
16014 __tmp.put_i32_le(self.relative_alt);
16015 __tmp.put_i16_le(self.vx);
16016 __tmp.put_i16_le(self.vy);
16017 __tmp.put_i16_le(self.vz);
16018 __tmp.put_u16_le(self.hdg);
16019 if matches!(version, MavlinkVersion::V2) {
16020 let len = __tmp.len();
16021 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16022 } else {
16023 __tmp.len()
16024 }
16025 }
16026}
16027#[doc = "id: 336"]
16028#[doc = "Configure cellular modems. This message is re-emitted as an acknowledgement by the modem. The message may also be explicitly requested using MAV_CMD_REQUEST_MESSAGE."]
16029#[derive(Debug, Clone, PartialEq)]
16030#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
16031#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
16032pub struct CELLULAR_CONFIG_DATA {
16033 #[doc = "Enable/disable LTE. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response."]
16034 pub enable_lte: u8,
16035 #[doc = "Enable/disable PIN on the SIM card. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response."]
16036 pub enable_pin: u8,
16037 #[doc = "PIN sent to the SIM card. Blank when PIN is disabled. Empty when message is sent back as a response."]
16038 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
16039 pub pin: [u8; 16],
16040 #[doc = "New PIN when changing the PIN. Blank to leave it unchanged. Empty when message is sent back as a response."]
16041 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
16042 pub new_pin: [u8; 16],
16043 #[doc = "Name of the cellular APN. Blank to leave it unchanged. Current APN when sent back as a response."]
16044 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
16045 pub apn: [u8; 32],
16046 #[doc = "Required PUK code in case the user failed to authenticate 3 times with the PIN. Empty when message is sent back as a response."]
16047 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
16048 pub puk: [u8; 16],
16049 #[doc = "Enable/disable roaming. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response."]
16050 pub roaming: u8,
16051 #[doc = "Message acceptance response (sent back to GS)."]
16052 pub response: CellularConfigResponse,
16053}
16054impl CELLULAR_CONFIG_DATA {
16055 pub const ENCODED_LEN: usize = 84usize;
16056 pub const DEFAULT: Self = Self {
16057 enable_lte: 0_u8,
16058 enable_pin: 0_u8,
16059 pin: [0_u8; 16usize],
16060 new_pin: [0_u8; 16usize],
16061 apn: [0_u8; 32usize],
16062 puk: [0_u8; 16usize],
16063 roaming: 0_u8,
16064 response: CellularConfigResponse::DEFAULT,
16065 };
16066 #[cfg(feature = "arbitrary")]
16067 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
16068 use arbitrary::{Arbitrary, Unstructured};
16069 let mut buf = [0u8; 1024];
16070 rng.fill_bytes(&mut buf);
16071 let mut unstructured = Unstructured::new(&buf);
16072 Self::arbitrary(&mut unstructured).unwrap_or_default()
16073 }
16074}
16075impl Default for CELLULAR_CONFIG_DATA {
16076 fn default() -> Self {
16077 Self::DEFAULT.clone()
16078 }
16079}
16080impl MessageData for CELLULAR_CONFIG_DATA {
16081 type Message = MavMessage;
16082 const ID: u32 = 336u32;
16083 const NAME: &'static str = "CELLULAR_CONFIG";
16084 const EXTRA_CRC: u8 = 245u8;
16085 const ENCODED_LEN: usize = 84usize;
16086 fn deser(
16087 _version: MavlinkVersion,
16088 __input: &[u8],
16089 ) -> Result<Self, ::mavlink_core::error::ParserError> {
16090 let avail_len = __input.len();
16091 let mut payload_buf = [0; Self::ENCODED_LEN];
16092 let mut buf = if avail_len < Self::ENCODED_LEN {
16093 payload_buf[0..avail_len].copy_from_slice(__input);
16094 Bytes::new(&payload_buf)
16095 } else {
16096 Bytes::new(__input)
16097 };
16098 let mut __struct = Self::default();
16099 __struct.enable_lte = buf.get_u8();
16100 __struct.enable_pin = buf.get_u8();
16101 for v in &mut __struct.pin {
16102 let val = buf.get_u8();
16103 *v = val;
16104 }
16105 for v in &mut __struct.new_pin {
16106 let val = buf.get_u8();
16107 *v = val;
16108 }
16109 for v in &mut __struct.apn {
16110 let val = buf.get_u8();
16111 *v = val;
16112 }
16113 for v in &mut __struct.puk {
16114 let val = buf.get_u8();
16115 *v = val;
16116 }
16117 __struct.roaming = buf.get_u8();
16118 let tmp = buf.get_u8();
16119 __struct.response =
16120 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
16121 enum_type: "CellularConfigResponse",
16122 value: tmp as u32,
16123 })?;
16124 Ok(__struct)
16125 }
16126 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16127 let mut __tmp = BytesMut::new(bytes);
16128 #[allow(clippy::absurd_extreme_comparisons)]
16129 #[allow(unused_comparisons)]
16130 if __tmp.remaining() < Self::ENCODED_LEN {
16131 panic!(
16132 "buffer is too small (need {} bytes, but got {})",
16133 Self::ENCODED_LEN,
16134 __tmp.remaining(),
16135 )
16136 }
16137 __tmp.put_u8(self.enable_lte);
16138 __tmp.put_u8(self.enable_pin);
16139 for val in &self.pin {
16140 __tmp.put_u8(*val);
16141 }
16142 for val in &self.new_pin {
16143 __tmp.put_u8(*val);
16144 }
16145 for val in &self.apn {
16146 __tmp.put_u8(*val);
16147 }
16148 for val in &self.puk {
16149 __tmp.put_u8(*val);
16150 }
16151 __tmp.put_u8(self.roaming);
16152 __tmp.put_u8(self.response as u8);
16153 if matches!(version, MavlinkVersion::V2) {
16154 let len = __tmp.len();
16155 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16156 } else {
16157 __tmp.len()
16158 }
16159 }
16160}
16161#[doc = "id: 437"]
16162#[doc = "A change to the sequence number indicates that the set of AVAILABLE_MODES has changed. A receiver must re-request all available modes whenever the sequence number changes. This is only emitted after the first change and should then be broadcast at low rate (nominally 0.3 Hz) and on change. See <https://mavlink.io/en/services/standard_modes.html>."]
16163#[derive(Debug, Clone, PartialEq)]
16164#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
16165#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
16166pub struct AVAILABLE_MODES_MONITOR_DATA {
16167 #[doc = "Sequence number. The value iterates sequentially whenever AVAILABLE_MODES changes (e.g. support for a new mode is added/removed dynamically)."]
16168 pub seq: u8,
16169}
16170impl AVAILABLE_MODES_MONITOR_DATA {
16171 pub const ENCODED_LEN: usize = 1usize;
16172 pub const DEFAULT: Self = Self { seq: 0_u8 };
16173 #[cfg(feature = "arbitrary")]
16174 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
16175 use arbitrary::{Arbitrary, Unstructured};
16176 let mut buf = [0u8; 1024];
16177 rng.fill_bytes(&mut buf);
16178 let mut unstructured = Unstructured::new(&buf);
16179 Self::arbitrary(&mut unstructured).unwrap_or_default()
16180 }
16181}
16182impl Default for AVAILABLE_MODES_MONITOR_DATA {
16183 fn default() -> Self {
16184 Self::DEFAULT.clone()
16185 }
16186}
16187impl MessageData for AVAILABLE_MODES_MONITOR_DATA {
16188 type Message = MavMessage;
16189 const ID: u32 = 437u32;
16190 const NAME: &'static str = "AVAILABLE_MODES_MONITOR";
16191 const EXTRA_CRC: u8 = 30u8;
16192 const ENCODED_LEN: usize = 1usize;
16193 fn deser(
16194 _version: MavlinkVersion,
16195 __input: &[u8],
16196 ) -> Result<Self, ::mavlink_core::error::ParserError> {
16197 let avail_len = __input.len();
16198 let mut payload_buf = [0; Self::ENCODED_LEN];
16199 let mut buf = if avail_len < Self::ENCODED_LEN {
16200 payload_buf[0..avail_len].copy_from_slice(__input);
16201 Bytes::new(&payload_buf)
16202 } else {
16203 Bytes::new(__input)
16204 };
16205 let mut __struct = Self::default();
16206 __struct.seq = buf.get_u8();
16207 Ok(__struct)
16208 }
16209 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16210 let mut __tmp = BytesMut::new(bytes);
16211 #[allow(clippy::absurd_extreme_comparisons)]
16212 #[allow(unused_comparisons)]
16213 if __tmp.remaining() < Self::ENCODED_LEN {
16214 panic!(
16215 "buffer is too small (need {} bytes, but got {})",
16216 Self::ENCODED_LEN,
16217 __tmp.remaining(),
16218 )
16219 }
16220 __tmp.put_u8(self.seq);
16221 if matches!(version, MavlinkVersion::V2) {
16222 let len = __tmp.len();
16223 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16224 } else {
16225 __tmp.len()
16226 }
16227 }
16228}
16229#[doc = "id: 25"]
16230#[doc = "The positioning status, as reported by GPS. This message is intended to display status information about each satellite visible to the receiver. See message GLOBAL_POSITION_INT for the global position estimate. This message can contain information for up to 20 satellites."]
16231#[derive(Debug, Clone, PartialEq)]
16232#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
16233#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
16234pub struct GPS_STATUS_DATA {
16235 #[doc = "Number of satellites visible"]
16236 pub satellites_visible: u8,
16237 #[doc = "Global satellite ID"]
16238 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
16239 pub satellite_prn: [u8; 20],
16240 #[doc = "0: Satellite not used, 1: used for localization"]
16241 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
16242 pub satellite_used: [u8; 20],
16243 #[doc = "Elevation (0: right on top of receiver, 90: on the horizon) of satellite"]
16244 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
16245 pub satellite_elevation: [u8; 20],
16246 #[doc = "Direction of satellite, 0: 0 deg, 255: 360 deg."]
16247 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
16248 pub satellite_azimuth: [u8; 20],
16249 #[doc = "Signal to noise ratio of satellite"]
16250 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
16251 pub satellite_snr: [u8; 20],
16252}
16253impl GPS_STATUS_DATA {
16254 pub const ENCODED_LEN: usize = 101usize;
16255 pub const DEFAULT: Self = Self {
16256 satellites_visible: 0_u8,
16257 satellite_prn: [0_u8; 20usize],
16258 satellite_used: [0_u8; 20usize],
16259 satellite_elevation: [0_u8; 20usize],
16260 satellite_azimuth: [0_u8; 20usize],
16261 satellite_snr: [0_u8; 20usize],
16262 };
16263 #[cfg(feature = "arbitrary")]
16264 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
16265 use arbitrary::{Arbitrary, Unstructured};
16266 let mut buf = [0u8; 1024];
16267 rng.fill_bytes(&mut buf);
16268 let mut unstructured = Unstructured::new(&buf);
16269 Self::arbitrary(&mut unstructured).unwrap_or_default()
16270 }
16271}
16272impl Default for GPS_STATUS_DATA {
16273 fn default() -> Self {
16274 Self::DEFAULT.clone()
16275 }
16276}
16277impl MessageData for GPS_STATUS_DATA {
16278 type Message = MavMessage;
16279 const ID: u32 = 25u32;
16280 const NAME: &'static str = "GPS_STATUS";
16281 const EXTRA_CRC: u8 = 23u8;
16282 const ENCODED_LEN: usize = 101usize;
16283 fn deser(
16284 _version: MavlinkVersion,
16285 __input: &[u8],
16286 ) -> Result<Self, ::mavlink_core::error::ParserError> {
16287 let avail_len = __input.len();
16288 let mut payload_buf = [0; Self::ENCODED_LEN];
16289 let mut buf = if avail_len < Self::ENCODED_LEN {
16290 payload_buf[0..avail_len].copy_from_slice(__input);
16291 Bytes::new(&payload_buf)
16292 } else {
16293 Bytes::new(__input)
16294 };
16295 let mut __struct = Self::default();
16296 __struct.satellites_visible = buf.get_u8();
16297 for v in &mut __struct.satellite_prn {
16298 let val = buf.get_u8();
16299 *v = val;
16300 }
16301 for v in &mut __struct.satellite_used {
16302 let val = buf.get_u8();
16303 *v = val;
16304 }
16305 for v in &mut __struct.satellite_elevation {
16306 let val = buf.get_u8();
16307 *v = val;
16308 }
16309 for v in &mut __struct.satellite_azimuth {
16310 let val = buf.get_u8();
16311 *v = val;
16312 }
16313 for v in &mut __struct.satellite_snr {
16314 let val = buf.get_u8();
16315 *v = val;
16316 }
16317 Ok(__struct)
16318 }
16319 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16320 let mut __tmp = BytesMut::new(bytes);
16321 #[allow(clippy::absurd_extreme_comparisons)]
16322 #[allow(unused_comparisons)]
16323 if __tmp.remaining() < Self::ENCODED_LEN {
16324 panic!(
16325 "buffer is too small (need {} bytes, but got {})",
16326 Self::ENCODED_LEN,
16327 __tmp.remaining(),
16328 )
16329 }
16330 __tmp.put_u8(self.satellites_visible);
16331 for val in &self.satellite_prn {
16332 __tmp.put_u8(*val);
16333 }
16334 for val in &self.satellite_used {
16335 __tmp.put_u8(*val);
16336 }
16337 for val in &self.satellite_elevation {
16338 __tmp.put_u8(*val);
16339 }
16340 for val in &self.satellite_azimuth {
16341 __tmp.put_u8(*val);
16342 }
16343 for val in &self.satellite_snr {
16344 __tmp.put_u8(*val);
16345 }
16346 if matches!(version, MavlinkVersion::V2) {
16347 let len = __tmp.len();
16348 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16349 } else {
16350 __tmp.len()
16351 }
16352 }
16353}
16354#[doc = "id: 29"]
16355#[doc = "The pressure readings for the typical setup of one absolute and differential pressure sensor. The units are as specified in each field."]
16356#[derive(Debug, Clone, PartialEq)]
16357#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
16358#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
16359pub struct SCALED_PRESSURE_DATA {
16360 #[doc = "Timestamp (time since system boot)."]
16361 pub time_boot_ms: u32,
16362 #[doc = "Absolute pressure"]
16363 pub press_abs: f32,
16364 #[doc = "Differential pressure 1"]
16365 pub press_diff: f32,
16366 #[doc = "Absolute pressure temperature"]
16367 pub temperature: i16,
16368 #[doc = "Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC."]
16369 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
16370 pub temperature_press_diff: i16,
16371}
16372impl SCALED_PRESSURE_DATA {
16373 pub const ENCODED_LEN: usize = 16usize;
16374 pub const DEFAULT: Self = Self {
16375 time_boot_ms: 0_u32,
16376 press_abs: 0.0_f32,
16377 press_diff: 0.0_f32,
16378 temperature: 0_i16,
16379 temperature_press_diff: 0_i16,
16380 };
16381 #[cfg(feature = "arbitrary")]
16382 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
16383 use arbitrary::{Arbitrary, Unstructured};
16384 let mut buf = [0u8; 1024];
16385 rng.fill_bytes(&mut buf);
16386 let mut unstructured = Unstructured::new(&buf);
16387 Self::arbitrary(&mut unstructured).unwrap_or_default()
16388 }
16389}
16390impl Default for SCALED_PRESSURE_DATA {
16391 fn default() -> Self {
16392 Self::DEFAULT.clone()
16393 }
16394}
16395impl MessageData for SCALED_PRESSURE_DATA {
16396 type Message = MavMessage;
16397 const ID: u32 = 29u32;
16398 const NAME: &'static str = "SCALED_PRESSURE";
16399 const EXTRA_CRC: u8 = 115u8;
16400 const ENCODED_LEN: usize = 16usize;
16401 fn deser(
16402 _version: MavlinkVersion,
16403 __input: &[u8],
16404 ) -> Result<Self, ::mavlink_core::error::ParserError> {
16405 let avail_len = __input.len();
16406 let mut payload_buf = [0; Self::ENCODED_LEN];
16407 let mut buf = if avail_len < Self::ENCODED_LEN {
16408 payload_buf[0..avail_len].copy_from_slice(__input);
16409 Bytes::new(&payload_buf)
16410 } else {
16411 Bytes::new(__input)
16412 };
16413 let mut __struct = Self::default();
16414 __struct.time_boot_ms = buf.get_u32_le();
16415 __struct.press_abs = buf.get_f32_le();
16416 __struct.press_diff = buf.get_f32_le();
16417 __struct.temperature = buf.get_i16_le();
16418 __struct.temperature_press_diff = buf.get_i16_le();
16419 Ok(__struct)
16420 }
16421 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16422 let mut __tmp = BytesMut::new(bytes);
16423 #[allow(clippy::absurd_extreme_comparisons)]
16424 #[allow(unused_comparisons)]
16425 if __tmp.remaining() < Self::ENCODED_LEN {
16426 panic!(
16427 "buffer is too small (need {} bytes, but got {})",
16428 Self::ENCODED_LEN,
16429 __tmp.remaining(),
16430 )
16431 }
16432 __tmp.put_u32_le(self.time_boot_ms);
16433 __tmp.put_f32_le(self.press_abs);
16434 __tmp.put_f32_le(self.press_diff);
16435 __tmp.put_i16_le(self.temperature);
16436 __tmp.put_i16_le(self.temperature_press_diff);
16437 if matches!(version, MavlinkVersion::V2) {
16438 let len = __tmp.len();
16439 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16440 } else {
16441 __tmp.len()
16442 }
16443 }
16444}
16445#[doc = "id: 100"]
16446#[doc = "Optical flow from a flow sensor (e.g. optical mouse sensor)."]
16447#[derive(Debug, Clone, PartialEq)]
16448#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
16449#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
16450pub struct OPTICAL_FLOW_DATA {
16451 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
16452 pub time_usec: u64,
16453 #[doc = "Flow in x-sensor direction, angular-speed compensated"]
16454 pub flow_comp_m_x: f32,
16455 #[doc = "Flow in y-sensor direction, angular-speed compensated"]
16456 pub flow_comp_m_y: f32,
16457 #[doc = "Ground distance. Positive value: distance known. Negative value: Unknown distance"]
16458 pub ground_distance: f32,
16459 #[doc = "Flow in x-sensor direction"]
16460 pub flow_x: i16,
16461 #[doc = "Flow in y-sensor direction"]
16462 pub flow_y: i16,
16463 #[doc = "Sensor ID"]
16464 pub sensor_id: u8,
16465 #[doc = "Optical flow quality / confidence. 0: bad, 255: maximum quality"]
16466 pub quality: u8,
16467 #[doc = "Flow rate about X axis"]
16468 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
16469 pub flow_rate_x: f32,
16470 #[doc = "Flow rate about Y axis"]
16471 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
16472 pub flow_rate_y: f32,
16473}
16474impl OPTICAL_FLOW_DATA {
16475 pub const ENCODED_LEN: usize = 34usize;
16476 pub const DEFAULT: Self = Self {
16477 time_usec: 0_u64,
16478 flow_comp_m_x: 0.0_f32,
16479 flow_comp_m_y: 0.0_f32,
16480 ground_distance: 0.0_f32,
16481 flow_x: 0_i16,
16482 flow_y: 0_i16,
16483 sensor_id: 0_u8,
16484 quality: 0_u8,
16485 flow_rate_x: 0.0_f32,
16486 flow_rate_y: 0.0_f32,
16487 };
16488 #[cfg(feature = "arbitrary")]
16489 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
16490 use arbitrary::{Arbitrary, Unstructured};
16491 let mut buf = [0u8; 1024];
16492 rng.fill_bytes(&mut buf);
16493 let mut unstructured = Unstructured::new(&buf);
16494 Self::arbitrary(&mut unstructured).unwrap_or_default()
16495 }
16496}
16497impl Default for OPTICAL_FLOW_DATA {
16498 fn default() -> Self {
16499 Self::DEFAULT.clone()
16500 }
16501}
16502impl MessageData for OPTICAL_FLOW_DATA {
16503 type Message = MavMessage;
16504 const ID: u32 = 100u32;
16505 const NAME: &'static str = "OPTICAL_FLOW";
16506 const EXTRA_CRC: u8 = 175u8;
16507 const ENCODED_LEN: usize = 34usize;
16508 fn deser(
16509 _version: MavlinkVersion,
16510 __input: &[u8],
16511 ) -> Result<Self, ::mavlink_core::error::ParserError> {
16512 let avail_len = __input.len();
16513 let mut payload_buf = [0; Self::ENCODED_LEN];
16514 let mut buf = if avail_len < Self::ENCODED_LEN {
16515 payload_buf[0..avail_len].copy_from_slice(__input);
16516 Bytes::new(&payload_buf)
16517 } else {
16518 Bytes::new(__input)
16519 };
16520 let mut __struct = Self::default();
16521 __struct.time_usec = buf.get_u64_le();
16522 __struct.flow_comp_m_x = buf.get_f32_le();
16523 __struct.flow_comp_m_y = buf.get_f32_le();
16524 __struct.ground_distance = buf.get_f32_le();
16525 __struct.flow_x = buf.get_i16_le();
16526 __struct.flow_y = buf.get_i16_le();
16527 __struct.sensor_id = buf.get_u8();
16528 __struct.quality = buf.get_u8();
16529 __struct.flow_rate_x = buf.get_f32_le();
16530 __struct.flow_rate_y = buf.get_f32_le();
16531 Ok(__struct)
16532 }
16533 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16534 let mut __tmp = BytesMut::new(bytes);
16535 #[allow(clippy::absurd_extreme_comparisons)]
16536 #[allow(unused_comparisons)]
16537 if __tmp.remaining() < Self::ENCODED_LEN {
16538 panic!(
16539 "buffer is too small (need {} bytes, but got {})",
16540 Self::ENCODED_LEN,
16541 __tmp.remaining(),
16542 )
16543 }
16544 __tmp.put_u64_le(self.time_usec);
16545 __tmp.put_f32_le(self.flow_comp_m_x);
16546 __tmp.put_f32_le(self.flow_comp_m_y);
16547 __tmp.put_f32_le(self.ground_distance);
16548 __tmp.put_i16_le(self.flow_x);
16549 __tmp.put_i16_le(self.flow_y);
16550 __tmp.put_u8(self.sensor_id);
16551 __tmp.put_u8(self.quality);
16552 __tmp.put_f32_le(self.flow_rate_x);
16553 __tmp.put_f32_le(self.flow_rate_y);
16554 if matches!(version, MavlinkVersion::V2) {
16555 let len = __tmp.len();
16556 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16557 } else {
16558 __tmp.len()
16559 }
16560 }
16561}
16562#[doc = "id: 12918"]
16563#[doc = "Transmitter (remote ID system) is enabled and ready to start sending location and other required information. This is streamed by transmitter. A flight controller uses it as a condition to arm."]
16564#[derive(Debug, Clone, PartialEq)]
16565#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
16566#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
16567pub struct OPEN_DRONE_ID_ARM_STATUS_DATA {
16568 #[doc = "Status level indicating if arming is allowed."]
16569 pub status: MavOdidArmStatus,
16570 #[doc = "Text error message, should be empty if status is good to arm. Fill with nulls in unused portion."]
16571 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
16572 pub error: [u8; 50],
16573}
16574impl OPEN_DRONE_ID_ARM_STATUS_DATA {
16575 pub const ENCODED_LEN: usize = 51usize;
16576 pub const DEFAULT: Self = Self {
16577 status: MavOdidArmStatus::DEFAULT,
16578 error: [0_u8; 50usize],
16579 };
16580 #[cfg(feature = "arbitrary")]
16581 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
16582 use arbitrary::{Arbitrary, Unstructured};
16583 let mut buf = [0u8; 1024];
16584 rng.fill_bytes(&mut buf);
16585 let mut unstructured = Unstructured::new(&buf);
16586 Self::arbitrary(&mut unstructured).unwrap_or_default()
16587 }
16588}
16589impl Default for OPEN_DRONE_ID_ARM_STATUS_DATA {
16590 fn default() -> Self {
16591 Self::DEFAULT.clone()
16592 }
16593}
16594impl MessageData for OPEN_DRONE_ID_ARM_STATUS_DATA {
16595 type Message = MavMessage;
16596 const ID: u32 = 12918u32;
16597 const NAME: &'static str = "OPEN_DRONE_ID_ARM_STATUS";
16598 const EXTRA_CRC: u8 = 139u8;
16599 const ENCODED_LEN: usize = 51usize;
16600 fn deser(
16601 _version: MavlinkVersion,
16602 __input: &[u8],
16603 ) -> Result<Self, ::mavlink_core::error::ParserError> {
16604 let avail_len = __input.len();
16605 let mut payload_buf = [0; Self::ENCODED_LEN];
16606 let mut buf = if avail_len < Self::ENCODED_LEN {
16607 payload_buf[0..avail_len].copy_from_slice(__input);
16608 Bytes::new(&payload_buf)
16609 } else {
16610 Bytes::new(__input)
16611 };
16612 let mut __struct = Self::default();
16613 let tmp = buf.get_u8();
16614 __struct.status =
16615 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
16616 enum_type: "MavOdidArmStatus",
16617 value: tmp as u32,
16618 })?;
16619 for v in &mut __struct.error {
16620 let val = buf.get_u8();
16621 *v = val;
16622 }
16623 Ok(__struct)
16624 }
16625 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16626 let mut __tmp = BytesMut::new(bytes);
16627 #[allow(clippy::absurd_extreme_comparisons)]
16628 #[allow(unused_comparisons)]
16629 if __tmp.remaining() < Self::ENCODED_LEN {
16630 panic!(
16631 "buffer is too small (need {} bytes, but got {})",
16632 Self::ENCODED_LEN,
16633 __tmp.remaining(),
16634 )
16635 }
16636 __tmp.put_u8(self.status as u8);
16637 for val in &self.error {
16638 __tmp.put_u8(*val);
16639 }
16640 if matches!(version, MavlinkVersion::V2) {
16641 let len = __tmp.len();
16642 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16643 } else {
16644 __tmp.len()
16645 }
16646 }
16647}
16648#[doc = "id: 70"]
16649#[doc = "The RAW values of the RC channels sent to the MAV to override info received from the RC radio. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. Note carefully the semantic differences between the first 8 channels and the subsequent channels."]
16650#[derive(Debug, Clone, PartialEq)]
16651#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
16652#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
16653pub struct RC_CHANNELS_OVERRIDE_DATA {
16654 #[doc = "RC channel 1 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio."]
16655 pub chan1_raw: u16,
16656 #[doc = "RC channel 2 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio."]
16657 pub chan2_raw: u16,
16658 #[doc = "RC channel 3 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio."]
16659 pub chan3_raw: u16,
16660 #[doc = "RC channel 4 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio."]
16661 pub chan4_raw: u16,
16662 #[doc = "RC channel 5 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio."]
16663 pub chan5_raw: u16,
16664 #[doc = "RC channel 6 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio."]
16665 pub chan6_raw: u16,
16666 #[doc = "RC channel 7 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio."]
16667 pub chan7_raw: u16,
16668 #[doc = "RC channel 8 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio."]
16669 pub chan8_raw: u16,
16670 #[doc = "System ID"]
16671 pub target_system: u8,
16672 #[doc = "Component ID"]
16673 pub target_component: u8,
16674 #[doc = "RC channel 9 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
16675 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
16676 pub chan9_raw: u16,
16677 #[doc = "RC channel 10 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
16678 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
16679 pub chan10_raw: u16,
16680 #[doc = "RC channel 11 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
16681 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
16682 pub chan11_raw: u16,
16683 #[doc = "RC channel 12 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
16684 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
16685 pub chan12_raw: u16,
16686 #[doc = "RC channel 13 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
16687 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
16688 pub chan13_raw: u16,
16689 #[doc = "RC channel 14 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
16690 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
16691 pub chan14_raw: u16,
16692 #[doc = "RC channel 15 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
16693 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
16694 pub chan15_raw: u16,
16695 #[doc = "RC channel 16 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
16696 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
16697 pub chan16_raw: u16,
16698 #[doc = "RC channel 17 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
16699 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
16700 pub chan17_raw: u16,
16701 #[doc = "RC channel 18 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
16702 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
16703 pub chan18_raw: u16,
16704}
16705impl RC_CHANNELS_OVERRIDE_DATA {
16706 pub const ENCODED_LEN: usize = 38usize;
16707 pub const DEFAULT: Self = Self {
16708 chan1_raw: 0_u16,
16709 chan2_raw: 0_u16,
16710 chan3_raw: 0_u16,
16711 chan4_raw: 0_u16,
16712 chan5_raw: 0_u16,
16713 chan6_raw: 0_u16,
16714 chan7_raw: 0_u16,
16715 chan8_raw: 0_u16,
16716 target_system: 0_u8,
16717 target_component: 0_u8,
16718 chan9_raw: 0_u16,
16719 chan10_raw: 0_u16,
16720 chan11_raw: 0_u16,
16721 chan12_raw: 0_u16,
16722 chan13_raw: 0_u16,
16723 chan14_raw: 0_u16,
16724 chan15_raw: 0_u16,
16725 chan16_raw: 0_u16,
16726 chan17_raw: 0_u16,
16727 chan18_raw: 0_u16,
16728 };
16729 #[cfg(feature = "arbitrary")]
16730 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
16731 use arbitrary::{Arbitrary, Unstructured};
16732 let mut buf = [0u8; 1024];
16733 rng.fill_bytes(&mut buf);
16734 let mut unstructured = Unstructured::new(&buf);
16735 Self::arbitrary(&mut unstructured).unwrap_or_default()
16736 }
16737}
16738impl Default for RC_CHANNELS_OVERRIDE_DATA {
16739 fn default() -> Self {
16740 Self::DEFAULT.clone()
16741 }
16742}
16743impl MessageData for RC_CHANNELS_OVERRIDE_DATA {
16744 type Message = MavMessage;
16745 const ID: u32 = 70u32;
16746 const NAME: &'static str = "RC_CHANNELS_OVERRIDE";
16747 const EXTRA_CRC: u8 = 124u8;
16748 const ENCODED_LEN: usize = 38usize;
16749 fn deser(
16750 _version: MavlinkVersion,
16751 __input: &[u8],
16752 ) -> Result<Self, ::mavlink_core::error::ParserError> {
16753 let avail_len = __input.len();
16754 let mut payload_buf = [0; Self::ENCODED_LEN];
16755 let mut buf = if avail_len < Self::ENCODED_LEN {
16756 payload_buf[0..avail_len].copy_from_slice(__input);
16757 Bytes::new(&payload_buf)
16758 } else {
16759 Bytes::new(__input)
16760 };
16761 let mut __struct = Self::default();
16762 __struct.chan1_raw = buf.get_u16_le();
16763 __struct.chan2_raw = buf.get_u16_le();
16764 __struct.chan3_raw = buf.get_u16_le();
16765 __struct.chan4_raw = buf.get_u16_le();
16766 __struct.chan5_raw = buf.get_u16_le();
16767 __struct.chan6_raw = buf.get_u16_le();
16768 __struct.chan7_raw = buf.get_u16_le();
16769 __struct.chan8_raw = buf.get_u16_le();
16770 __struct.target_system = buf.get_u8();
16771 __struct.target_component = buf.get_u8();
16772 __struct.chan9_raw = buf.get_u16_le();
16773 __struct.chan10_raw = buf.get_u16_le();
16774 __struct.chan11_raw = buf.get_u16_le();
16775 __struct.chan12_raw = buf.get_u16_le();
16776 __struct.chan13_raw = buf.get_u16_le();
16777 __struct.chan14_raw = buf.get_u16_le();
16778 __struct.chan15_raw = buf.get_u16_le();
16779 __struct.chan16_raw = buf.get_u16_le();
16780 __struct.chan17_raw = buf.get_u16_le();
16781 __struct.chan18_raw = buf.get_u16_le();
16782 Ok(__struct)
16783 }
16784 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16785 let mut __tmp = BytesMut::new(bytes);
16786 #[allow(clippy::absurd_extreme_comparisons)]
16787 #[allow(unused_comparisons)]
16788 if __tmp.remaining() < Self::ENCODED_LEN {
16789 panic!(
16790 "buffer is too small (need {} bytes, but got {})",
16791 Self::ENCODED_LEN,
16792 __tmp.remaining(),
16793 )
16794 }
16795 __tmp.put_u16_le(self.chan1_raw);
16796 __tmp.put_u16_le(self.chan2_raw);
16797 __tmp.put_u16_le(self.chan3_raw);
16798 __tmp.put_u16_le(self.chan4_raw);
16799 __tmp.put_u16_le(self.chan5_raw);
16800 __tmp.put_u16_le(self.chan6_raw);
16801 __tmp.put_u16_le(self.chan7_raw);
16802 __tmp.put_u16_le(self.chan8_raw);
16803 __tmp.put_u8(self.target_system);
16804 __tmp.put_u8(self.target_component);
16805 __tmp.put_u16_le(self.chan9_raw);
16806 __tmp.put_u16_le(self.chan10_raw);
16807 __tmp.put_u16_le(self.chan11_raw);
16808 __tmp.put_u16_le(self.chan12_raw);
16809 __tmp.put_u16_le(self.chan13_raw);
16810 __tmp.put_u16_le(self.chan14_raw);
16811 __tmp.put_u16_le(self.chan15_raw);
16812 __tmp.put_u16_le(self.chan16_raw);
16813 __tmp.put_u16_le(self.chan17_raw);
16814 __tmp.put_u16_le(self.chan18_raw);
16815 if matches!(version, MavlinkVersion::V2) {
16816 let len = __tmp.len();
16817 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16818 } else {
16819 __tmp.len()
16820 }
16821 }
16822}
16823#[doc = "id: 120"]
16824#[doc = "Reply to LOG_REQUEST_DATA."]
16825#[derive(Debug, Clone, PartialEq)]
16826#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
16827#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
16828pub struct LOG_DATA_DATA {
16829 #[doc = "Offset into the log"]
16830 pub ofs: u32,
16831 #[doc = "Log id (from LOG_ENTRY reply)"]
16832 pub id: u16,
16833 #[doc = "Number of bytes (zero for end of log)"]
16834 pub count: u8,
16835 #[doc = "log data"]
16836 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
16837 pub data: [u8; 90],
16838}
16839impl LOG_DATA_DATA {
16840 pub const ENCODED_LEN: usize = 97usize;
16841 pub const DEFAULT: Self = Self {
16842 ofs: 0_u32,
16843 id: 0_u16,
16844 count: 0_u8,
16845 data: [0_u8; 90usize],
16846 };
16847 #[cfg(feature = "arbitrary")]
16848 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
16849 use arbitrary::{Arbitrary, Unstructured};
16850 let mut buf = [0u8; 1024];
16851 rng.fill_bytes(&mut buf);
16852 let mut unstructured = Unstructured::new(&buf);
16853 Self::arbitrary(&mut unstructured).unwrap_or_default()
16854 }
16855}
16856impl Default for LOG_DATA_DATA {
16857 fn default() -> Self {
16858 Self::DEFAULT.clone()
16859 }
16860}
16861impl MessageData for LOG_DATA_DATA {
16862 type Message = MavMessage;
16863 const ID: u32 = 120u32;
16864 const NAME: &'static str = "LOG_DATA";
16865 const EXTRA_CRC: u8 = 134u8;
16866 const ENCODED_LEN: usize = 97usize;
16867 fn deser(
16868 _version: MavlinkVersion,
16869 __input: &[u8],
16870 ) -> Result<Self, ::mavlink_core::error::ParserError> {
16871 let avail_len = __input.len();
16872 let mut payload_buf = [0; Self::ENCODED_LEN];
16873 let mut buf = if avail_len < Self::ENCODED_LEN {
16874 payload_buf[0..avail_len].copy_from_slice(__input);
16875 Bytes::new(&payload_buf)
16876 } else {
16877 Bytes::new(__input)
16878 };
16879 let mut __struct = Self::default();
16880 __struct.ofs = buf.get_u32_le();
16881 __struct.id = buf.get_u16_le();
16882 __struct.count = buf.get_u8();
16883 for v in &mut __struct.data {
16884 let val = buf.get_u8();
16885 *v = val;
16886 }
16887 Ok(__struct)
16888 }
16889 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16890 let mut __tmp = BytesMut::new(bytes);
16891 #[allow(clippy::absurd_extreme_comparisons)]
16892 #[allow(unused_comparisons)]
16893 if __tmp.remaining() < Self::ENCODED_LEN {
16894 panic!(
16895 "buffer is too small (need {} bytes, but got {})",
16896 Self::ENCODED_LEN,
16897 __tmp.remaining(),
16898 )
16899 }
16900 __tmp.put_u32_le(self.ofs);
16901 __tmp.put_u16_le(self.id);
16902 __tmp.put_u8(self.count);
16903 for val in &self.data {
16904 __tmp.put_u8(*val);
16905 }
16906 if matches!(version, MavlinkVersion::V2) {
16907 let len = __tmp.len();
16908 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16909 } else {
16910 __tmp.len()
16911 }
16912 }
16913}
16914#[doc = "id: 43"]
16915#[doc = "Request the overall list of mission items from the system/component."]
16916#[derive(Debug, Clone, PartialEq)]
16917#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
16918#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
16919pub struct MISSION_REQUEST_LIST_DATA {
16920 #[doc = "System ID"]
16921 pub target_system: u8,
16922 #[doc = "Component ID"]
16923 pub target_component: u8,
16924 #[doc = "Mission type."]
16925 #[cfg_attr(feature = "serde", serde(default))]
16926 pub mission_type: MavMissionType,
16927}
16928impl MISSION_REQUEST_LIST_DATA {
16929 pub const ENCODED_LEN: usize = 3usize;
16930 pub const DEFAULT: Self = Self {
16931 target_system: 0_u8,
16932 target_component: 0_u8,
16933 mission_type: MavMissionType::DEFAULT,
16934 };
16935 #[cfg(feature = "arbitrary")]
16936 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
16937 use arbitrary::{Arbitrary, Unstructured};
16938 let mut buf = [0u8; 1024];
16939 rng.fill_bytes(&mut buf);
16940 let mut unstructured = Unstructured::new(&buf);
16941 Self::arbitrary(&mut unstructured).unwrap_or_default()
16942 }
16943}
16944impl Default for MISSION_REQUEST_LIST_DATA {
16945 fn default() -> Self {
16946 Self::DEFAULT.clone()
16947 }
16948}
16949impl MessageData for MISSION_REQUEST_LIST_DATA {
16950 type Message = MavMessage;
16951 const ID: u32 = 43u32;
16952 const NAME: &'static str = "MISSION_REQUEST_LIST";
16953 const EXTRA_CRC: u8 = 132u8;
16954 const ENCODED_LEN: usize = 3usize;
16955 fn deser(
16956 _version: MavlinkVersion,
16957 __input: &[u8],
16958 ) -> Result<Self, ::mavlink_core::error::ParserError> {
16959 let avail_len = __input.len();
16960 let mut payload_buf = [0; Self::ENCODED_LEN];
16961 let mut buf = if avail_len < Self::ENCODED_LEN {
16962 payload_buf[0..avail_len].copy_from_slice(__input);
16963 Bytes::new(&payload_buf)
16964 } else {
16965 Bytes::new(__input)
16966 };
16967 let mut __struct = Self::default();
16968 __struct.target_system = buf.get_u8();
16969 __struct.target_component = buf.get_u8();
16970 let tmp = buf.get_u8();
16971 __struct.mission_type =
16972 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
16973 enum_type: "MavMissionType",
16974 value: tmp as u32,
16975 })?;
16976 Ok(__struct)
16977 }
16978 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16979 let mut __tmp = BytesMut::new(bytes);
16980 #[allow(clippy::absurd_extreme_comparisons)]
16981 #[allow(unused_comparisons)]
16982 if __tmp.remaining() < Self::ENCODED_LEN {
16983 panic!(
16984 "buffer is too small (need {} bytes, but got {})",
16985 Self::ENCODED_LEN,
16986 __tmp.remaining(),
16987 )
16988 }
16989 __tmp.put_u8(self.target_system);
16990 __tmp.put_u8(self.target_component);
16991 __tmp.put_u8(self.mission_type as u8);
16992 if matches!(version, MavlinkVersion::V2) {
16993 let len = __tmp.len();
16994 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16995 } else {
16996 __tmp.len()
16997 }
16998 }
16999}
17000#[doc = "id: 61"]
17001#[doc = "The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0)."]
17002#[derive(Debug, Clone, PartialEq)]
17003#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17004#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17005pub struct ATTITUDE_QUATERNION_COV_DATA {
17006 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
17007 pub time_usec: u64,
17008 #[doc = "Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)"]
17009 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
17010 pub q: [f32; 4],
17011 #[doc = "Roll angular speed"]
17012 pub rollspeed: f32,
17013 #[doc = "Pitch angular speed"]
17014 pub pitchspeed: f32,
17015 #[doc = "Yaw angular speed"]
17016 pub yawspeed: f32,
17017 #[doc = "Row-major representation of a 3x3 attitude covariance matrix (states: roll, pitch, yaw; first three entries are the first ROW, next three entries are the second row, etc.). If unknown, assign NaN value to first element in the array."]
17018 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
17019 pub covariance: [f32; 9],
17020}
17021impl ATTITUDE_QUATERNION_COV_DATA {
17022 pub const ENCODED_LEN: usize = 72usize;
17023 pub const DEFAULT: Self = Self {
17024 time_usec: 0_u64,
17025 q: [0.0_f32; 4usize],
17026 rollspeed: 0.0_f32,
17027 pitchspeed: 0.0_f32,
17028 yawspeed: 0.0_f32,
17029 covariance: [0.0_f32; 9usize],
17030 };
17031 #[cfg(feature = "arbitrary")]
17032 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17033 use arbitrary::{Arbitrary, Unstructured};
17034 let mut buf = [0u8; 1024];
17035 rng.fill_bytes(&mut buf);
17036 let mut unstructured = Unstructured::new(&buf);
17037 Self::arbitrary(&mut unstructured).unwrap_or_default()
17038 }
17039}
17040impl Default for ATTITUDE_QUATERNION_COV_DATA {
17041 fn default() -> Self {
17042 Self::DEFAULT.clone()
17043 }
17044}
17045impl MessageData for ATTITUDE_QUATERNION_COV_DATA {
17046 type Message = MavMessage;
17047 const ID: u32 = 61u32;
17048 const NAME: &'static str = "ATTITUDE_QUATERNION_COV";
17049 const EXTRA_CRC: u8 = 167u8;
17050 const ENCODED_LEN: usize = 72usize;
17051 fn deser(
17052 _version: MavlinkVersion,
17053 __input: &[u8],
17054 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17055 let avail_len = __input.len();
17056 let mut payload_buf = [0; Self::ENCODED_LEN];
17057 let mut buf = if avail_len < Self::ENCODED_LEN {
17058 payload_buf[0..avail_len].copy_from_slice(__input);
17059 Bytes::new(&payload_buf)
17060 } else {
17061 Bytes::new(__input)
17062 };
17063 let mut __struct = Self::default();
17064 __struct.time_usec = buf.get_u64_le();
17065 for v in &mut __struct.q {
17066 let val = buf.get_f32_le();
17067 *v = val;
17068 }
17069 __struct.rollspeed = buf.get_f32_le();
17070 __struct.pitchspeed = buf.get_f32_le();
17071 __struct.yawspeed = buf.get_f32_le();
17072 for v in &mut __struct.covariance {
17073 let val = buf.get_f32_le();
17074 *v = val;
17075 }
17076 Ok(__struct)
17077 }
17078 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17079 let mut __tmp = BytesMut::new(bytes);
17080 #[allow(clippy::absurd_extreme_comparisons)]
17081 #[allow(unused_comparisons)]
17082 if __tmp.remaining() < Self::ENCODED_LEN {
17083 panic!(
17084 "buffer is too small (need {} bytes, but got {})",
17085 Self::ENCODED_LEN,
17086 __tmp.remaining(),
17087 )
17088 }
17089 __tmp.put_u64_le(self.time_usec);
17090 for val in &self.q {
17091 __tmp.put_f32_le(*val);
17092 }
17093 __tmp.put_f32_le(self.rollspeed);
17094 __tmp.put_f32_le(self.pitchspeed);
17095 __tmp.put_f32_le(self.yawspeed);
17096 for val in &self.covariance {
17097 __tmp.put_f32_le(*val);
17098 }
17099 if matches!(version, MavlinkVersion::V2) {
17100 let len = __tmp.len();
17101 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17102 } else {
17103 __tmp.len()
17104 }
17105 }
17106}
17107#[doc = "id: 87"]
17108#[doc = "Reports the current commanded vehicle position, velocity, and acceleration as specified by the autopilot. This should match the commands sent in SET_POSITION_TARGET_GLOBAL_INT if the vehicle is being controlled this way."]
17109#[derive(Debug, Clone, PartialEq)]
17110#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17111#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17112pub struct POSITION_TARGET_GLOBAL_INT_DATA {
17113 #[doc = "Timestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency."]
17114 pub time_boot_ms: u32,
17115 #[doc = "Latitude in WGS84 frame"]
17116 pub lat_int: i32,
17117 #[doc = "Longitude in WGS84 frame"]
17118 pub lon_int: i32,
17119 #[doc = "Altitude (MSL, AGL or relative to home altitude, depending on frame)"]
17120 pub alt: f32,
17121 #[doc = "X velocity in NED frame"]
17122 pub vx: f32,
17123 #[doc = "Y velocity in NED frame"]
17124 pub vy: f32,
17125 #[doc = "Z velocity in NED frame"]
17126 pub vz: f32,
17127 #[doc = "X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
17128 pub afx: f32,
17129 #[doc = "Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
17130 pub afy: f32,
17131 #[doc = "Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
17132 pub afz: f32,
17133 #[doc = "yaw setpoint"]
17134 pub yaw: f32,
17135 #[doc = "yaw rate setpoint"]
17136 pub yaw_rate: f32,
17137 #[doc = "Bitmap to indicate which dimensions should be ignored by the vehicle."]
17138 pub type_mask: PositionTargetTypemask,
17139 #[doc = "Valid options are: MAV_FRAME_GLOBAL = 0, MAV_FRAME_GLOBAL_RELATIVE_ALT = 3, MAV_FRAME_GLOBAL_TERRAIN_ALT = 10 (MAV_FRAME_GLOBAL_INT, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT are allowed synonyms, but have been deprecated)"]
17140 pub coordinate_frame: MavFrame,
17141}
17142impl POSITION_TARGET_GLOBAL_INT_DATA {
17143 pub const ENCODED_LEN: usize = 51usize;
17144 pub const DEFAULT: Self = Self {
17145 time_boot_ms: 0_u32,
17146 lat_int: 0_i32,
17147 lon_int: 0_i32,
17148 alt: 0.0_f32,
17149 vx: 0.0_f32,
17150 vy: 0.0_f32,
17151 vz: 0.0_f32,
17152 afx: 0.0_f32,
17153 afy: 0.0_f32,
17154 afz: 0.0_f32,
17155 yaw: 0.0_f32,
17156 yaw_rate: 0.0_f32,
17157 type_mask: PositionTargetTypemask::DEFAULT,
17158 coordinate_frame: MavFrame::DEFAULT,
17159 };
17160 #[cfg(feature = "arbitrary")]
17161 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17162 use arbitrary::{Arbitrary, Unstructured};
17163 let mut buf = [0u8; 1024];
17164 rng.fill_bytes(&mut buf);
17165 let mut unstructured = Unstructured::new(&buf);
17166 Self::arbitrary(&mut unstructured).unwrap_or_default()
17167 }
17168}
17169impl Default for POSITION_TARGET_GLOBAL_INT_DATA {
17170 fn default() -> Self {
17171 Self::DEFAULT.clone()
17172 }
17173}
17174impl MessageData for POSITION_TARGET_GLOBAL_INT_DATA {
17175 type Message = MavMessage;
17176 const ID: u32 = 87u32;
17177 const NAME: &'static str = "POSITION_TARGET_GLOBAL_INT";
17178 const EXTRA_CRC: u8 = 150u8;
17179 const ENCODED_LEN: usize = 51usize;
17180 fn deser(
17181 _version: MavlinkVersion,
17182 __input: &[u8],
17183 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17184 let avail_len = __input.len();
17185 let mut payload_buf = [0; Self::ENCODED_LEN];
17186 let mut buf = if avail_len < Self::ENCODED_LEN {
17187 payload_buf[0..avail_len].copy_from_slice(__input);
17188 Bytes::new(&payload_buf)
17189 } else {
17190 Bytes::new(__input)
17191 };
17192 let mut __struct = Self::default();
17193 __struct.time_boot_ms = buf.get_u32_le();
17194 __struct.lat_int = buf.get_i32_le();
17195 __struct.lon_int = buf.get_i32_le();
17196 __struct.alt = buf.get_f32_le();
17197 __struct.vx = buf.get_f32_le();
17198 __struct.vy = buf.get_f32_le();
17199 __struct.vz = buf.get_f32_le();
17200 __struct.afx = buf.get_f32_le();
17201 __struct.afy = buf.get_f32_le();
17202 __struct.afz = buf.get_f32_le();
17203 __struct.yaw = buf.get_f32_le();
17204 __struct.yaw_rate = buf.get_f32_le();
17205 let tmp = buf.get_u16_le();
17206 __struct.type_mask = PositionTargetTypemask::from_bits(
17207 tmp & PositionTargetTypemask::all().bits(),
17208 )
17209 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
17210 flag_type: "PositionTargetTypemask",
17211 value: tmp as u32,
17212 })?;
17213 let tmp = buf.get_u8();
17214 __struct.coordinate_frame =
17215 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
17216 enum_type: "MavFrame",
17217 value: tmp as u32,
17218 })?;
17219 Ok(__struct)
17220 }
17221 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17222 let mut __tmp = BytesMut::new(bytes);
17223 #[allow(clippy::absurd_extreme_comparisons)]
17224 #[allow(unused_comparisons)]
17225 if __tmp.remaining() < Self::ENCODED_LEN {
17226 panic!(
17227 "buffer is too small (need {} bytes, but got {})",
17228 Self::ENCODED_LEN,
17229 __tmp.remaining(),
17230 )
17231 }
17232 __tmp.put_u32_le(self.time_boot_ms);
17233 __tmp.put_i32_le(self.lat_int);
17234 __tmp.put_i32_le(self.lon_int);
17235 __tmp.put_f32_le(self.alt);
17236 __tmp.put_f32_le(self.vx);
17237 __tmp.put_f32_le(self.vy);
17238 __tmp.put_f32_le(self.vz);
17239 __tmp.put_f32_le(self.afx);
17240 __tmp.put_f32_le(self.afy);
17241 __tmp.put_f32_le(self.afz);
17242 __tmp.put_f32_le(self.yaw);
17243 __tmp.put_f32_le(self.yaw_rate);
17244 __tmp.put_u16_le(self.type_mask.bits());
17245 __tmp.put_u8(self.coordinate_frame as u8);
17246 if matches!(version, MavlinkVersion::V2) {
17247 let len = __tmp.len();
17248 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17249 } else {
17250 __tmp.len()
17251 }
17252 }
17253}
17254#[doc = "id: 128"]
17255#[doc = "RTK GPS data. Gives information on the relative baseline calculation the GPS is reporting."]
17256#[derive(Debug, Clone, PartialEq)]
17257#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17258#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17259pub struct GPS2_RTK_DATA {
17260 #[doc = "Time since boot of last baseline message received."]
17261 pub time_last_baseline_ms: u32,
17262 #[doc = "GPS Time of Week of last baseline"]
17263 pub tow: u32,
17264 #[doc = "Current baseline in ECEF x or NED north component."]
17265 pub baseline_a_mm: i32,
17266 #[doc = "Current baseline in ECEF y or NED east component."]
17267 pub baseline_b_mm: i32,
17268 #[doc = "Current baseline in ECEF z or NED down component."]
17269 pub baseline_c_mm: i32,
17270 #[doc = "Current estimate of baseline accuracy."]
17271 pub accuracy: u32,
17272 #[doc = "Current number of integer ambiguity hypotheses."]
17273 pub iar_num_hypotheses: i32,
17274 #[doc = "GPS Week Number of last baseline"]
17275 pub wn: u16,
17276 #[doc = "Identification of connected RTK receiver."]
17277 pub rtk_receiver_id: u8,
17278 #[doc = "GPS-specific health report for RTK data."]
17279 pub rtk_health: u8,
17280 #[doc = "Rate of baseline messages being received by GPS"]
17281 pub rtk_rate: u8,
17282 #[doc = "Current number of sats used for RTK calculation."]
17283 pub nsats: u8,
17284 #[doc = "Coordinate system of baseline"]
17285 pub baseline_coords_type: RtkBaselineCoordinateSystem,
17286}
17287impl GPS2_RTK_DATA {
17288 pub const ENCODED_LEN: usize = 35usize;
17289 pub const DEFAULT: Self = Self {
17290 time_last_baseline_ms: 0_u32,
17291 tow: 0_u32,
17292 baseline_a_mm: 0_i32,
17293 baseline_b_mm: 0_i32,
17294 baseline_c_mm: 0_i32,
17295 accuracy: 0_u32,
17296 iar_num_hypotheses: 0_i32,
17297 wn: 0_u16,
17298 rtk_receiver_id: 0_u8,
17299 rtk_health: 0_u8,
17300 rtk_rate: 0_u8,
17301 nsats: 0_u8,
17302 baseline_coords_type: RtkBaselineCoordinateSystem::DEFAULT,
17303 };
17304 #[cfg(feature = "arbitrary")]
17305 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17306 use arbitrary::{Arbitrary, Unstructured};
17307 let mut buf = [0u8; 1024];
17308 rng.fill_bytes(&mut buf);
17309 let mut unstructured = Unstructured::new(&buf);
17310 Self::arbitrary(&mut unstructured).unwrap_or_default()
17311 }
17312}
17313impl Default for GPS2_RTK_DATA {
17314 fn default() -> Self {
17315 Self::DEFAULT.clone()
17316 }
17317}
17318impl MessageData for GPS2_RTK_DATA {
17319 type Message = MavMessage;
17320 const ID: u32 = 128u32;
17321 const NAME: &'static str = "GPS2_RTK";
17322 const EXTRA_CRC: u8 = 226u8;
17323 const ENCODED_LEN: usize = 35usize;
17324 fn deser(
17325 _version: MavlinkVersion,
17326 __input: &[u8],
17327 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17328 let avail_len = __input.len();
17329 let mut payload_buf = [0; Self::ENCODED_LEN];
17330 let mut buf = if avail_len < Self::ENCODED_LEN {
17331 payload_buf[0..avail_len].copy_from_slice(__input);
17332 Bytes::new(&payload_buf)
17333 } else {
17334 Bytes::new(__input)
17335 };
17336 let mut __struct = Self::default();
17337 __struct.time_last_baseline_ms = buf.get_u32_le();
17338 __struct.tow = buf.get_u32_le();
17339 __struct.baseline_a_mm = buf.get_i32_le();
17340 __struct.baseline_b_mm = buf.get_i32_le();
17341 __struct.baseline_c_mm = buf.get_i32_le();
17342 __struct.accuracy = buf.get_u32_le();
17343 __struct.iar_num_hypotheses = buf.get_i32_le();
17344 __struct.wn = buf.get_u16_le();
17345 __struct.rtk_receiver_id = buf.get_u8();
17346 __struct.rtk_health = buf.get_u8();
17347 __struct.rtk_rate = buf.get_u8();
17348 __struct.nsats = buf.get_u8();
17349 let tmp = buf.get_u8();
17350 __struct.baseline_coords_type =
17351 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
17352 enum_type: "RtkBaselineCoordinateSystem",
17353 value: tmp as u32,
17354 })?;
17355 Ok(__struct)
17356 }
17357 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17358 let mut __tmp = BytesMut::new(bytes);
17359 #[allow(clippy::absurd_extreme_comparisons)]
17360 #[allow(unused_comparisons)]
17361 if __tmp.remaining() < Self::ENCODED_LEN {
17362 panic!(
17363 "buffer is too small (need {} bytes, but got {})",
17364 Self::ENCODED_LEN,
17365 __tmp.remaining(),
17366 )
17367 }
17368 __tmp.put_u32_le(self.time_last_baseline_ms);
17369 __tmp.put_u32_le(self.tow);
17370 __tmp.put_i32_le(self.baseline_a_mm);
17371 __tmp.put_i32_le(self.baseline_b_mm);
17372 __tmp.put_i32_le(self.baseline_c_mm);
17373 __tmp.put_u32_le(self.accuracy);
17374 __tmp.put_i32_le(self.iar_num_hypotheses);
17375 __tmp.put_u16_le(self.wn);
17376 __tmp.put_u8(self.rtk_receiver_id);
17377 __tmp.put_u8(self.rtk_health);
17378 __tmp.put_u8(self.rtk_rate);
17379 __tmp.put_u8(self.nsats);
17380 __tmp.put_u8(self.baseline_coords_type as u8);
17381 if matches!(version, MavlinkVersion::V2) {
17382 let len = __tmp.len();
17383 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17384 } else {
17385 __tmp.len()
17386 }
17387 }
17388}
17389#[doc = "id: 142"]
17390#[doc = "The autopilot is requesting a resource (file, binary, other type of data)."]
17391#[derive(Debug, Clone, PartialEq)]
17392#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17393#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17394pub struct RESOURCE_REQUEST_DATA {
17395 #[doc = "Request ID. This ID should be re-used when sending back URI contents"]
17396 pub request_id: u8,
17397 #[doc = "The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary"]
17398 pub uri_type: u8,
17399 #[doc = "The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum)"]
17400 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
17401 pub uri: [u8; 120],
17402 #[doc = "The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream."]
17403 pub transfer_type: u8,
17404 #[doc = "The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP)."]
17405 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
17406 pub storage: [u8; 120],
17407}
17408impl RESOURCE_REQUEST_DATA {
17409 pub const ENCODED_LEN: usize = 243usize;
17410 pub const DEFAULT: Self = Self {
17411 request_id: 0_u8,
17412 uri_type: 0_u8,
17413 uri: [0_u8; 120usize],
17414 transfer_type: 0_u8,
17415 storage: [0_u8; 120usize],
17416 };
17417 #[cfg(feature = "arbitrary")]
17418 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17419 use arbitrary::{Arbitrary, Unstructured};
17420 let mut buf = [0u8; 1024];
17421 rng.fill_bytes(&mut buf);
17422 let mut unstructured = Unstructured::new(&buf);
17423 Self::arbitrary(&mut unstructured).unwrap_or_default()
17424 }
17425}
17426impl Default for RESOURCE_REQUEST_DATA {
17427 fn default() -> Self {
17428 Self::DEFAULT.clone()
17429 }
17430}
17431impl MessageData for RESOURCE_REQUEST_DATA {
17432 type Message = MavMessage;
17433 const ID: u32 = 142u32;
17434 const NAME: &'static str = "RESOURCE_REQUEST";
17435 const EXTRA_CRC: u8 = 72u8;
17436 const ENCODED_LEN: usize = 243usize;
17437 fn deser(
17438 _version: MavlinkVersion,
17439 __input: &[u8],
17440 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17441 let avail_len = __input.len();
17442 let mut payload_buf = [0; Self::ENCODED_LEN];
17443 let mut buf = if avail_len < Self::ENCODED_LEN {
17444 payload_buf[0..avail_len].copy_from_slice(__input);
17445 Bytes::new(&payload_buf)
17446 } else {
17447 Bytes::new(__input)
17448 };
17449 let mut __struct = Self::default();
17450 __struct.request_id = buf.get_u8();
17451 __struct.uri_type = buf.get_u8();
17452 for v in &mut __struct.uri {
17453 let val = buf.get_u8();
17454 *v = val;
17455 }
17456 __struct.transfer_type = buf.get_u8();
17457 for v in &mut __struct.storage {
17458 let val = buf.get_u8();
17459 *v = val;
17460 }
17461 Ok(__struct)
17462 }
17463 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17464 let mut __tmp = BytesMut::new(bytes);
17465 #[allow(clippy::absurd_extreme_comparisons)]
17466 #[allow(unused_comparisons)]
17467 if __tmp.remaining() < Self::ENCODED_LEN {
17468 panic!(
17469 "buffer is too small (need {} bytes, but got {})",
17470 Self::ENCODED_LEN,
17471 __tmp.remaining(),
17472 )
17473 }
17474 __tmp.put_u8(self.request_id);
17475 __tmp.put_u8(self.uri_type);
17476 for val in &self.uri {
17477 __tmp.put_u8(*val);
17478 }
17479 __tmp.put_u8(self.transfer_type);
17480 for val in &self.storage {
17481 __tmp.put_u8(*val);
17482 }
17483 if matches!(version, MavlinkVersion::V2) {
17484 let len = __tmp.len();
17485 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17486 } else {
17487 __tmp.len()
17488 }
17489 }
17490}
17491#[doc = "id: 230"]
17492#[doc = "Estimator status message including flags, innovation test ratios and estimated accuracies. The flags message is an integer bitmask containing information on which EKF outputs are valid. See the ESTIMATOR_STATUS_FLAGS enum definition for further information. The innovation test ratios show the magnitude of the sensor innovation divided by the innovation check threshold. Under normal operation the innovation test ratios should be below 0.5 with occasional values up to 1.0. Values greater than 1.0 should be rare under normal operation and indicate that a measurement has been rejected by the filter. The user should be notified if an innovation test ratio greater than 1.0 is recorded. Notifications for values in the range between 0.5 and 1.0 should be optional and controllable by the user."]
17493#[derive(Debug, Clone, PartialEq)]
17494#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17495#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17496pub struct ESTIMATOR_STATUS_DATA {
17497 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
17498 pub time_usec: u64,
17499 #[doc = "Velocity innovation test ratio"]
17500 pub vel_ratio: f32,
17501 #[doc = "Horizontal position innovation test ratio"]
17502 pub pos_horiz_ratio: f32,
17503 #[doc = "Vertical position innovation test ratio"]
17504 pub pos_vert_ratio: f32,
17505 #[doc = "Magnetometer innovation test ratio"]
17506 pub mag_ratio: f32,
17507 #[doc = "Height above terrain innovation test ratio"]
17508 pub hagl_ratio: f32,
17509 #[doc = "True airspeed innovation test ratio"]
17510 pub tas_ratio: f32,
17511 #[doc = "Horizontal position 1-STD accuracy relative to the EKF local origin"]
17512 pub pos_horiz_accuracy: f32,
17513 #[doc = "Vertical position 1-STD accuracy relative to the EKF local origin"]
17514 pub pos_vert_accuracy: f32,
17515 #[doc = "Bitmap indicating which EKF outputs are valid."]
17516 pub flags: EstimatorStatusFlags,
17517}
17518impl ESTIMATOR_STATUS_DATA {
17519 pub const ENCODED_LEN: usize = 42usize;
17520 pub const DEFAULT: Self = Self {
17521 time_usec: 0_u64,
17522 vel_ratio: 0.0_f32,
17523 pos_horiz_ratio: 0.0_f32,
17524 pos_vert_ratio: 0.0_f32,
17525 mag_ratio: 0.0_f32,
17526 hagl_ratio: 0.0_f32,
17527 tas_ratio: 0.0_f32,
17528 pos_horiz_accuracy: 0.0_f32,
17529 pos_vert_accuracy: 0.0_f32,
17530 flags: EstimatorStatusFlags::DEFAULT,
17531 };
17532 #[cfg(feature = "arbitrary")]
17533 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17534 use arbitrary::{Arbitrary, Unstructured};
17535 let mut buf = [0u8; 1024];
17536 rng.fill_bytes(&mut buf);
17537 let mut unstructured = Unstructured::new(&buf);
17538 Self::arbitrary(&mut unstructured).unwrap_or_default()
17539 }
17540}
17541impl Default for ESTIMATOR_STATUS_DATA {
17542 fn default() -> Self {
17543 Self::DEFAULT.clone()
17544 }
17545}
17546impl MessageData for ESTIMATOR_STATUS_DATA {
17547 type Message = MavMessage;
17548 const ID: u32 = 230u32;
17549 const NAME: &'static str = "ESTIMATOR_STATUS";
17550 const EXTRA_CRC: u8 = 163u8;
17551 const ENCODED_LEN: usize = 42usize;
17552 fn deser(
17553 _version: MavlinkVersion,
17554 __input: &[u8],
17555 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17556 let avail_len = __input.len();
17557 let mut payload_buf = [0; Self::ENCODED_LEN];
17558 let mut buf = if avail_len < Self::ENCODED_LEN {
17559 payload_buf[0..avail_len].copy_from_slice(__input);
17560 Bytes::new(&payload_buf)
17561 } else {
17562 Bytes::new(__input)
17563 };
17564 let mut __struct = Self::default();
17565 __struct.time_usec = buf.get_u64_le();
17566 __struct.vel_ratio = buf.get_f32_le();
17567 __struct.pos_horiz_ratio = buf.get_f32_le();
17568 __struct.pos_vert_ratio = buf.get_f32_le();
17569 __struct.mag_ratio = buf.get_f32_le();
17570 __struct.hagl_ratio = buf.get_f32_le();
17571 __struct.tas_ratio = buf.get_f32_le();
17572 __struct.pos_horiz_accuracy = buf.get_f32_le();
17573 __struct.pos_vert_accuracy = buf.get_f32_le();
17574 let tmp = buf.get_u16_le();
17575 __struct.flags = EstimatorStatusFlags::from_bits(tmp & EstimatorStatusFlags::all().bits())
17576 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
17577 flag_type: "EstimatorStatusFlags",
17578 value: tmp as u32,
17579 })?;
17580 Ok(__struct)
17581 }
17582 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17583 let mut __tmp = BytesMut::new(bytes);
17584 #[allow(clippy::absurd_extreme_comparisons)]
17585 #[allow(unused_comparisons)]
17586 if __tmp.remaining() < Self::ENCODED_LEN {
17587 panic!(
17588 "buffer is too small (need {} bytes, but got {})",
17589 Self::ENCODED_LEN,
17590 __tmp.remaining(),
17591 )
17592 }
17593 __tmp.put_u64_le(self.time_usec);
17594 __tmp.put_f32_le(self.vel_ratio);
17595 __tmp.put_f32_le(self.pos_horiz_ratio);
17596 __tmp.put_f32_le(self.pos_vert_ratio);
17597 __tmp.put_f32_le(self.mag_ratio);
17598 __tmp.put_f32_le(self.hagl_ratio);
17599 __tmp.put_f32_le(self.tas_ratio);
17600 __tmp.put_f32_le(self.pos_horiz_accuracy);
17601 __tmp.put_f32_le(self.pos_vert_accuracy);
17602 __tmp.put_u16_le(self.flags.bits());
17603 if matches!(version, MavlinkVersion::V2) {
17604 let len = __tmp.len();
17605 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17606 } else {
17607 __tmp.len()
17608 }
17609 }
17610}
17611#[doc = "id: 390"]
17612#[doc = "Hardware status sent by an onboard computer."]
17613#[derive(Debug, Clone, PartialEq)]
17614#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17615#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17616pub struct ONBOARD_COMPUTER_STATUS_DATA {
17617 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
17618 pub time_usec: u64,
17619 #[doc = "Time since system boot."]
17620 pub uptime: u32,
17621 #[doc = "Amount of used RAM on the component system. A value of UINT32_MAX implies the field is unused."]
17622 pub ram_usage: u32,
17623 #[doc = "Total amount of RAM on the component system. A value of UINT32_MAX implies the field is unused."]
17624 pub ram_total: u32,
17625 #[doc = "Storage type: 0: HDD, 1: SSD, 2: EMMC, 3: SD card (non-removable), 4: SD card (removable). A value of UINT32_MAX implies the field is unused."]
17626 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
17627 pub storage_type: [u32; 4],
17628 #[doc = "Amount of used storage space on the component system. A value of UINT32_MAX implies the field is unused."]
17629 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
17630 pub storage_usage: [u32; 4],
17631 #[doc = "Total amount of storage space on the component system. A value of UINT32_MAX implies the field is unused."]
17632 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
17633 pub storage_total: [u32; 4],
17634 #[doc = "Link type: 0-9: UART, 10-19: Wired network, 20-29: Wifi, 30-39: Point-to-point proprietary, 40-49: Mesh proprietary"]
17635 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
17636 pub link_type: [u32; 6],
17637 #[doc = "Network traffic from the component system. A value of UINT32_MAX implies the field is unused."]
17638 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
17639 pub link_tx_rate: [u32; 6],
17640 #[doc = "Network traffic to the component system. A value of UINT32_MAX implies the field is unused."]
17641 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
17642 pub link_rx_rate: [u32; 6],
17643 #[doc = "Network capacity from the component system. A value of UINT32_MAX implies the field is unused."]
17644 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
17645 pub link_tx_max: [u32; 6],
17646 #[doc = "Network capacity to the component system. A value of UINT32_MAX implies the field is unused."]
17647 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
17648 pub link_rx_max: [u32; 6],
17649 #[doc = "Fan speeds. A value of INT16_MAX implies the field is unused."]
17650 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
17651 pub fan_speed: [i16; 4],
17652 #[doc = "Type of the onboard computer: 0: Mission computer primary, 1: Mission computer backup 1, 2: Mission computer backup 2, 3: Compute node, 4-5: Compute spares, 6-9: Payload computers."]
17653 pub mavtype: u8,
17654 #[doc = "CPU usage on the component in percent (100 - idle). A value of UINT8_MAX implies the field is unused."]
17655 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
17656 pub cpu_cores: [u8; 8],
17657 #[doc = "Combined CPU usage as the last 10 slices of 100 MS (a histogram). This allows to identify spikes in load that max out the system, but only for a short amount of time. A value of UINT8_MAX implies the field is unused."]
17658 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
17659 pub cpu_combined: [u8; 10],
17660 #[doc = "GPU usage on the component in percent (100 - idle). A value of UINT8_MAX implies the field is unused."]
17661 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
17662 pub gpu_cores: [u8; 4],
17663 #[doc = "Combined GPU usage as the last 10 slices of 100 MS (a histogram). This allows to identify spikes in load that max out the system, but only for a short amount of time. A value of UINT8_MAX implies the field is unused."]
17664 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
17665 pub gpu_combined: [u8; 10],
17666 #[doc = "Temperature of the board. A value of INT8_MAX implies the field is unused."]
17667 pub temperature_board: i8,
17668 #[doc = "Temperature of the CPU core. A value of INT8_MAX implies the field is unused."]
17669 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
17670 pub temperature_core: [i8; 8],
17671}
17672impl ONBOARD_COMPUTER_STATUS_DATA {
17673 pub const ENCODED_LEN: usize = 238usize;
17674 pub const DEFAULT: Self = Self {
17675 time_usec: 0_u64,
17676 uptime: 0_u32,
17677 ram_usage: 0_u32,
17678 ram_total: 0_u32,
17679 storage_type: [0_u32; 4usize],
17680 storage_usage: [0_u32; 4usize],
17681 storage_total: [0_u32; 4usize],
17682 link_type: [0_u32; 6usize],
17683 link_tx_rate: [0_u32; 6usize],
17684 link_rx_rate: [0_u32; 6usize],
17685 link_tx_max: [0_u32; 6usize],
17686 link_rx_max: [0_u32; 6usize],
17687 fan_speed: [0_i16; 4usize],
17688 mavtype: 0_u8,
17689 cpu_cores: [0_u8; 8usize],
17690 cpu_combined: [0_u8; 10usize],
17691 gpu_cores: [0_u8; 4usize],
17692 gpu_combined: [0_u8; 10usize],
17693 temperature_board: 0_i8,
17694 temperature_core: [0_i8; 8usize],
17695 };
17696 #[cfg(feature = "arbitrary")]
17697 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17698 use arbitrary::{Arbitrary, Unstructured};
17699 let mut buf = [0u8; 1024];
17700 rng.fill_bytes(&mut buf);
17701 let mut unstructured = Unstructured::new(&buf);
17702 Self::arbitrary(&mut unstructured).unwrap_or_default()
17703 }
17704}
17705impl Default for ONBOARD_COMPUTER_STATUS_DATA {
17706 fn default() -> Self {
17707 Self::DEFAULT.clone()
17708 }
17709}
17710impl MessageData for ONBOARD_COMPUTER_STATUS_DATA {
17711 type Message = MavMessage;
17712 const ID: u32 = 390u32;
17713 const NAME: &'static str = "ONBOARD_COMPUTER_STATUS";
17714 const EXTRA_CRC: u8 = 156u8;
17715 const ENCODED_LEN: usize = 238usize;
17716 fn deser(
17717 _version: MavlinkVersion,
17718 __input: &[u8],
17719 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17720 let avail_len = __input.len();
17721 let mut payload_buf = [0; Self::ENCODED_LEN];
17722 let mut buf = if avail_len < Self::ENCODED_LEN {
17723 payload_buf[0..avail_len].copy_from_slice(__input);
17724 Bytes::new(&payload_buf)
17725 } else {
17726 Bytes::new(__input)
17727 };
17728 let mut __struct = Self::default();
17729 __struct.time_usec = buf.get_u64_le();
17730 __struct.uptime = buf.get_u32_le();
17731 __struct.ram_usage = buf.get_u32_le();
17732 __struct.ram_total = buf.get_u32_le();
17733 for v in &mut __struct.storage_type {
17734 let val = buf.get_u32_le();
17735 *v = val;
17736 }
17737 for v in &mut __struct.storage_usage {
17738 let val = buf.get_u32_le();
17739 *v = val;
17740 }
17741 for v in &mut __struct.storage_total {
17742 let val = buf.get_u32_le();
17743 *v = val;
17744 }
17745 for v in &mut __struct.link_type {
17746 let val = buf.get_u32_le();
17747 *v = val;
17748 }
17749 for v in &mut __struct.link_tx_rate {
17750 let val = buf.get_u32_le();
17751 *v = val;
17752 }
17753 for v in &mut __struct.link_rx_rate {
17754 let val = buf.get_u32_le();
17755 *v = val;
17756 }
17757 for v in &mut __struct.link_tx_max {
17758 let val = buf.get_u32_le();
17759 *v = val;
17760 }
17761 for v in &mut __struct.link_rx_max {
17762 let val = buf.get_u32_le();
17763 *v = val;
17764 }
17765 for v in &mut __struct.fan_speed {
17766 let val = buf.get_i16_le();
17767 *v = val;
17768 }
17769 __struct.mavtype = buf.get_u8();
17770 for v in &mut __struct.cpu_cores {
17771 let val = buf.get_u8();
17772 *v = val;
17773 }
17774 for v in &mut __struct.cpu_combined {
17775 let val = buf.get_u8();
17776 *v = val;
17777 }
17778 for v in &mut __struct.gpu_cores {
17779 let val = buf.get_u8();
17780 *v = val;
17781 }
17782 for v in &mut __struct.gpu_combined {
17783 let val = buf.get_u8();
17784 *v = val;
17785 }
17786 __struct.temperature_board = buf.get_i8();
17787 for v in &mut __struct.temperature_core {
17788 let val = buf.get_i8();
17789 *v = val;
17790 }
17791 Ok(__struct)
17792 }
17793 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17794 let mut __tmp = BytesMut::new(bytes);
17795 #[allow(clippy::absurd_extreme_comparisons)]
17796 #[allow(unused_comparisons)]
17797 if __tmp.remaining() < Self::ENCODED_LEN {
17798 panic!(
17799 "buffer is too small (need {} bytes, but got {})",
17800 Self::ENCODED_LEN,
17801 __tmp.remaining(),
17802 )
17803 }
17804 __tmp.put_u64_le(self.time_usec);
17805 __tmp.put_u32_le(self.uptime);
17806 __tmp.put_u32_le(self.ram_usage);
17807 __tmp.put_u32_le(self.ram_total);
17808 for val in &self.storage_type {
17809 __tmp.put_u32_le(*val);
17810 }
17811 for val in &self.storage_usage {
17812 __tmp.put_u32_le(*val);
17813 }
17814 for val in &self.storage_total {
17815 __tmp.put_u32_le(*val);
17816 }
17817 for val in &self.link_type {
17818 __tmp.put_u32_le(*val);
17819 }
17820 for val in &self.link_tx_rate {
17821 __tmp.put_u32_le(*val);
17822 }
17823 for val in &self.link_rx_rate {
17824 __tmp.put_u32_le(*val);
17825 }
17826 for val in &self.link_tx_max {
17827 __tmp.put_u32_le(*val);
17828 }
17829 for val in &self.link_rx_max {
17830 __tmp.put_u32_le(*val);
17831 }
17832 for val in &self.fan_speed {
17833 __tmp.put_i16_le(*val);
17834 }
17835 __tmp.put_u8(self.mavtype);
17836 for val in &self.cpu_cores {
17837 __tmp.put_u8(*val);
17838 }
17839 for val in &self.cpu_combined {
17840 __tmp.put_u8(*val);
17841 }
17842 for val in &self.gpu_cores {
17843 __tmp.put_u8(*val);
17844 }
17845 for val in &self.gpu_combined {
17846 __tmp.put_u8(*val);
17847 }
17848 __tmp.put_i8(self.temperature_board);
17849 for val in &self.temperature_core {
17850 __tmp.put_i8(*val);
17851 }
17852 if matches!(version, MavlinkVersion::V2) {
17853 let len = __tmp.len();
17854 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17855 } else {
17856 __tmp.len()
17857 }
17858 }
17859}
17860#[doc = "id: 8"]
17861#[doc = "Status generated in each node in the communication chain and injected into MAVLink stream."]
17862#[derive(Debug, Clone, PartialEq)]
17863#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17864#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17865pub struct LINK_NODE_STATUS_DATA {
17866 #[doc = "Timestamp (time since system boot)."]
17867 pub timestamp: u64,
17868 #[doc = "Transmit rate"]
17869 pub tx_rate: u32,
17870 #[doc = "Receive rate"]
17871 pub rx_rate: u32,
17872 #[doc = "Messages sent"]
17873 pub messages_sent: u32,
17874 #[doc = "Messages received (estimated from counting seq)"]
17875 pub messages_received: u32,
17876 #[doc = "Messages lost (estimated from counting seq)"]
17877 pub messages_lost: u32,
17878 #[doc = "Number of bytes that could not be parsed correctly."]
17879 pub rx_parse_err: u16,
17880 #[doc = "Transmit buffer overflows. This number wraps around as it reaches UINT16_MAX"]
17881 pub tx_overflows: u16,
17882 #[doc = "Receive buffer overflows. This number wraps around as it reaches UINT16_MAX"]
17883 pub rx_overflows: u16,
17884 #[doc = "Remaining free transmit buffer space"]
17885 pub tx_buf: u8,
17886 #[doc = "Remaining free receive buffer space"]
17887 pub rx_buf: u8,
17888}
17889impl LINK_NODE_STATUS_DATA {
17890 pub const ENCODED_LEN: usize = 36usize;
17891 pub const DEFAULT: Self = Self {
17892 timestamp: 0_u64,
17893 tx_rate: 0_u32,
17894 rx_rate: 0_u32,
17895 messages_sent: 0_u32,
17896 messages_received: 0_u32,
17897 messages_lost: 0_u32,
17898 rx_parse_err: 0_u16,
17899 tx_overflows: 0_u16,
17900 rx_overflows: 0_u16,
17901 tx_buf: 0_u8,
17902 rx_buf: 0_u8,
17903 };
17904 #[cfg(feature = "arbitrary")]
17905 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17906 use arbitrary::{Arbitrary, Unstructured};
17907 let mut buf = [0u8; 1024];
17908 rng.fill_bytes(&mut buf);
17909 let mut unstructured = Unstructured::new(&buf);
17910 Self::arbitrary(&mut unstructured).unwrap_or_default()
17911 }
17912}
17913impl Default for LINK_NODE_STATUS_DATA {
17914 fn default() -> Self {
17915 Self::DEFAULT.clone()
17916 }
17917}
17918impl MessageData for LINK_NODE_STATUS_DATA {
17919 type Message = MavMessage;
17920 const ID: u32 = 8u32;
17921 const NAME: &'static str = "LINK_NODE_STATUS";
17922 const EXTRA_CRC: u8 = 117u8;
17923 const ENCODED_LEN: usize = 36usize;
17924 fn deser(
17925 _version: MavlinkVersion,
17926 __input: &[u8],
17927 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17928 let avail_len = __input.len();
17929 let mut payload_buf = [0; Self::ENCODED_LEN];
17930 let mut buf = if avail_len < Self::ENCODED_LEN {
17931 payload_buf[0..avail_len].copy_from_slice(__input);
17932 Bytes::new(&payload_buf)
17933 } else {
17934 Bytes::new(__input)
17935 };
17936 let mut __struct = Self::default();
17937 __struct.timestamp = buf.get_u64_le();
17938 __struct.tx_rate = buf.get_u32_le();
17939 __struct.rx_rate = buf.get_u32_le();
17940 __struct.messages_sent = buf.get_u32_le();
17941 __struct.messages_received = buf.get_u32_le();
17942 __struct.messages_lost = buf.get_u32_le();
17943 __struct.rx_parse_err = buf.get_u16_le();
17944 __struct.tx_overflows = buf.get_u16_le();
17945 __struct.rx_overflows = buf.get_u16_le();
17946 __struct.tx_buf = buf.get_u8();
17947 __struct.rx_buf = buf.get_u8();
17948 Ok(__struct)
17949 }
17950 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17951 let mut __tmp = BytesMut::new(bytes);
17952 #[allow(clippy::absurd_extreme_comparisons)]
17953 #[allow(unused_comparisons)]
17954 if __tmp.remaining() < Self::ENCODED_LEN {
17955 panic!(
17956 "buffer is too small (need {} bytes, but got {})",
17957 Self::ENCODED_LEN,
17958 __tmp.remaining(),
17959 )
17960 }
17961 __tmp.put_u64_le(self.timestamp);
17962 __tmp.put_u32_le(self.tx_rate);
17963 __tmp.put_u32_le(self.rx_rate);
17964 __tmp.put_u32_le(self.messages_sent);
17965 __tmp.put_u32_le(self.messages_received);
17966 __tmp.put_u32_le(self.messages_lost);
17967 __tmp.put_u16_le(self.rx_parse_err);
17968 __tmp.put_u16_le(self.tx_overflows);
17969 __tmp.put_u16_le(self.rx_overflows);
17970 __tmp.put_u8(self.tx_buf);
17971 __tmp.put_u8(self.rx_buf);
17972 if matches!(version, MavlinkVersion::V2) {
17973 let len = __tmp.len();
17974 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17975 } else {
17976 __tmp.len()
17977 }
17978 }
17979}
17980#[doc = "id: 146"]
17981#[doc = "The smoothed, monotonic system state used to feed the control loops of the system."]
17982#[derive(Debug, Clone, PartialEq)]
17983#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17984#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17985pub struct CONTROL_SYSTEM_STATE_DATA {
17986 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
17987 pub time_usec: u64,
17988 #[doc = "X acceleration in body frame"]
17989 pub x_acc: f32,
17990 #[doc = "Y acceleration in body frame"]
17991 pub y_acc: f32,
17992 #[doc = "Z acceleration in body frame"]
17993 pub z_acc: f32,
17994 #[doc = "X velocity in body frame"]
17995 pub x_vel: f32,
17996 #[doc = "Y velocity in body frame"]
17997 pub y_vel: f32,
17998 #[doc = "Z velocity in body frame"]
17999 pub z_vel: f32,
18000 #[doc = "X position in local frame"]
18001 pub x_pos: f32,
18002 #[doc = "Y position in local frame"]
18003 pub y_pos: f32,
18004 #[doc = "Z position in local frame"]
18005 pub z_pos: f32,
18006 #[doc = "Airspeed, set to -1 if unknown"]
18007 pub airspeed: f32,
18008 #[doc = "Variance of body velocity estimate"]
18009 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
18010 pub vel_variance: [f32; 3],
18011 #[doc = "Variance in local position"]
18012 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
18013 pub pos_variance: [f32; 3],
18014 #[doc = "The attitude, represented as Quaternion"]
18015 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
18016 pub q: [f32; 4],
18017 #[doc = "Angular rate in roll axis"]
18018 pub roll_rate: f32,
18019 #[doc = "Angular rate in pitch axis"]
18020 pub pitch_rate: f32,
18021 #[doc = "Angular rate in yaw axis"]
18022 pub yaw_rate: f32,
18023}
18024impl CONTROL_SYSTEM_STATE_DATA {
18025 pub const ENCODED_LEN: usize = 100usize;
18026 pub const DEFAULT: Self = Self {
18027 time_usec: 0_u64,
18028 x_acc: 0.0_f32,
18029 y_acc: 0.0_f32,
18030 z_acc: 0.0_f32,
18031 x_vel: 0.0_f32,
18032 y_vel: 0.0_f32,
18033 z_vel: 0.0_f32,
18034 x_pos: 0.0_f32,
18035 y_pos: 0.0_f32,
18036 z_pos: 0.0_f32,
18037 airspeed: 0.0_f32,
18038 vel_variance: [0.0_f32; 3usize],
18039 pos_variance: [0.0_f32; 3usize],
18040 q: [0.0_f32; 4usize],
18041 roll_rate: 0.0_f32,
18042 pitch_rate: 0.0_f32,
18043 yaw_rate: 0.0_f32,
18044 };
18045 #[cfg(feature = "arbitrary")]
18046 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
18047 use arbitrary::{Arbitrary, Unstructured};
18048 let mut buf = [0u8; 1024];
18049 rng.fill_bytes(&mut buf);
18050 let mut unstructured = Unstructured::new(&buf);
18051 Self::arbitrary(&mut unstructured).unwrap_or_default()
18052 }
18053}
18054impl Default for CONTROL_SYSTEM_STATE_DATA {
18055 fn default() -> Self {
18056 Self::DEFAULT.clone()
18057 }
18058}
18059impl MessageData for CONTROL_SYSTEM_STATE_DATA {
18060 type Message = MavMessage;
18061 const ID: u32 = 146u32;
18062 const NAME: &'static str = "CONTROL_SYSTEM_STATE";
18063 const EXTRA_CRC: u8 = 103u8;
18064 const ENCODED_LEN: usize = 100usize;
18065 fn deser(
18066 _version: MavlinkVersion,
18067 __input: &[u8],
18068 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18069 let avail_len = __input.len();
18070 let mut payload_buf = [0; Self::ENCODED_LEN];
18071 let mut buf = if avail_len < Self::ENCODED_LEN {
18072 payload_buf[0..avail_len].copy_from_slice(__input);
18073 Bytes::new(&payload_buf)
18074 } else {
18075 Bytes::new(__input)
18076 };
18077 let mut __struct = Self::default();
18078 __struct.time_usec = buf.get_u64_le();
18079 __struct.x_acc = buf.get_f32_le();
18080 __struct.y_acc = buf.get_f32_le();
18081 __struct.z_acc = buf.get_f32_le();
18082 __struct.x_vel = buf.get_f32_le();
18083 __struct.y_vel = buf.get_f32_le();
18084 __struct.z_vel = buf.get_f32_le();
18085 __struct.x_pos = buf.get_f32_le();
18086 __struct.y_pos = buf.get_f32_le();
18087 __struct.z_pos = buf.get_f32_le();
18088 __struct.airspeed = buf.get_f32_le();
18089 for v in &mut __struct.vel_variance {
18090 let val = buf.get_f32_le();
18091 *v = val;
18092 }
18093 for v in &mut __struct.pos_variance {
18094 let val = buf.get_f32_le();
18095 *v = val;
18096 }
18097 for v in &mut __struct.q {
18098 let val = buf.get_f32_le();
18099 *v = val;
18100 }
18101 __struct.roll_rate = buf.get_f32_le();
18102 __struct.pitch_rate = buf.get_f32_le();
18103 __struct.yaw_rate = buf.get_f32_le();
18104 Ok(__struct)
18105 }
18106 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18107 let mut __tmp = BytesMut::new(bytes);
18108 #[allow(clippy::absurd_extreme_comparisons)]
18109 #[allow(unused_comparisons)]
18110 if __tmp.remaining() < Self::ENCODED_LEN {
18111 panic!(
18112 "buffer is too small (need {} bytes, but got {})",
18113 Self::ENCODED_LEN,
18114 __tmp.remaining(),
18115 )
18116 }
18117 __tmp.put_u64_le(self.time_usec);
18118 __tmp.put_f32_le(self.x_acc);
18119 __tmp.put_f32_le(self.y_acc);
18120 __tmp.put_f32_le(self.z_acc);
18121 __tmp.put_f32_le(self.x_vel);
18122 __tmp.put_f32_le(self.y_vel);
18123 __tmp.put_f32_le(self.z_vel);
18124 __tmp.put_f32_le(self.x_pos);
18125 __tmp.put_f32_le(self.y_pos);
18126 __tmp.put_f32_le(self.z_pos);
18127 __tmp.put_f32_le(self.airspeed);
18128 for val in &self.vel_variance {
18129 __tmp.put_f32_le(*val);
18130 }
18131 for val in &self.pos_variance {
18132 __tmp.put_f32_le(*val);
18133 }
18134 for val in &self.q {
18135 __tmp.put_f32_le(*val);
18136 }
18137 __tmp.put_f32_le(self.roll_rate);
18138 __tmp.put_f32_le(self.pitch_rate);
18139 __tmp.put_f32_le(self.yaw_rate);
18140 if matches!(version, MavlinkVersion::V2) {
18141 let len = __tmp.len();
18142 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18143 } else {
18144 __tmp.len()
18145 }
18146 }
18147}
18148#[doc = "id: 244"]
18149#[doc = "The interval between messages for a particular MAVLink message ID. This message is sent in response to the MAV_CMD_REQUEST_MESSAGE command with param1=244 (this message) and param2=message_id (the id of the message for which the interval is required). \tIt may also be sent in response to MAV_CMD_GET_MESSAGE_INTERVAL. \tThis interface replaces DATA_STREAM."]
18150#[derive(Debug, Clone, PartialEq)]
18151#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18152#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18153pub struct MESSAGE_INTERVAL_DATA {
18154 #[doc = "0 indicates the interval at which it is sent."]
18155 pub interval_us: i32,
18156 #[doc = "The ID of the requested MAVLink message. v1.0 is limited to 254 messages."]
18157 pub message_id: u16,
18158}
18159impl MESSAGE_INTERVAL_DATA {
18160 pub const ENCODED_LEN: usize = 6usize;
18161 pub const DEFAULT: Self = Self {
18162 interval_us: 0_i32,
18163 message_id: 0_u16,
18164 };
18165 #[cfg(feature = "arbitrary")]
18166 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
18167 use arbitrary::{Arbitrary, Unstructured};
18168 let mut buf = [0u8; 1024];
18169 rng.fill_bytes(&mut buf);
18170 let mut unstructured = Unstructured::new(&buf);
18171 Self::arbitrary(&mut unstructured).unwrap_or_default()
18172 }
18173}
18174impl Default for MESSAGE_INTERVAL_DATA {
18175 fn default() -> Self {
18176 Self::DEFAULT.clone()
18177 }
18178}
18179impl MessageData for MESSAGE_INTERVAL_DATA {
18180 type Message = MavMessage;
18181 const ID: u32 = 244u32;
18182 const NAME: &'static str = "MESSAGE_INTERVAL";
18183 const EXTRA_CRC: u8 = 95u8;
18184 const ENCODED_LEN: usize = 6usize;
18185 fn deser(
18186 _version: MavlinkVersion,
18187 __input: &[u8],
18188 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18189 let avail_len = __input.len();
18190 let mut payload_buf = [0; Self::ENCODED_LEN];
18191 let mut buf = if avail_len < Self::ENCODED_LEN {
18192 payload_buf[0..avail_len].copy_from_slice(__input);
18193 Bytes::new(&payload_buf)
18194 } else {
18195 Bytes::new(__input)
18196 };
18197 let mut __struct = Self::default();
18198 __struct.interval_us = buf.get_i32_le();
18199 __struct.message_id = buf.get_u16_le();
18200 Ok(__struct)
18201 }
18202 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18203 let mut __tmp = BytesMut::new(bytes);
18204 #[allow(clippy::absurd_extreme_comparisons)]
18205 #[allow(unused_comparisons)]
18206 if __tmp.remaining() < Self::ENCODED_LEN {
18207 panic!(
18208 "buffer is too small (need {} bytes, but got {})",
18209 Self::ENCODED_LEN,
18210 __tmp.remaining(),
18211 )
18212 }
18213 __tmp.put_i32_le(self.interval_us);
18214 __tmp.put_u16_le(self.message_id);
18215 if matches!(version, MavlinkVersion::V2) {
18216 let len = __tmp.len();
18217 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18218 } else {
18219 __tmp.len()
18220 }
18221 }
18222}
18223#[doc = "id: 331"]
18224#[doc = "Odometry message to communicate odometry information with an external interface. Fits ROS REP 147 standard for aerial vehicles (<http://www.ros.org/reps/rep-0147.html>)."]
18225#[derive(Debug, Clone, PartialEq)]
18226#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18227#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18228pub struct ODOMETRY_DATA {
18229 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
18230 pub time_usec: u64,
18231 #[doc = "X Position"]
18232 pub x: f32,
18233 #[doc = "Y Position"]
18234 pub y: f32,
18235 #[doc = "Z Position"]
18236 pub z: f32,
18237 #[doc = "Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)"]
18238 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
18239 pub q: [f32; 4],
18240 #[doc = "X linear speed"]
18241 pub vx: f32,
18242 #[doc = "Y linear speed"]
18243 pub vy: f32,
18244 #[doc = "Z linear speed"]
18245 pub vz: f32,
18246 #[doc = "Roll angular speed"]
18247 pub rollspeed: f32,
18248 #[doc = "Pitch angular speed"]
18249 pub pitchspeed: f32,
18250 #[doc = "Yaw angular speed"]
18251 pub yawspeed: f32,
18252 #[doc = "Row-major representation of a 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array."]
18253 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
18254 pub pose_covariance: [f32; 21],
18255 #[doc = "Row-major representation of a 6x6 velocity cross-covariance matrix upper right triangle (states: vx, vy, vz, rollspeed, pitchspeed, yawspeed; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array."]
18256 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
18257 pub velocity_covariance: [f32; 21],
18258 #[doc = "Coordinate frame of reference for the pose data."]
18259 pub frame_id: MavFrame,
18260 #[doc = "Coordinate frame of reference for the velocity in free space (twist) data."]
18261 pub child_frame_id: MavFrame,
18262 #[doc = "Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps."]
18263 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
18264 pub reset_counter: u8,
18265 #[doc = "Type of estimator that is providing the odometry."]
18266 #[cfg_attr(feature = "serde", serde(default))]
18267 pub estimator_type: MavEstimatorType,
18268 #[doc = "Optional odometry quality metric as a percentage. -1 = odometry has failed, 0 = unknown/unset quality, 1 = worst quality, 100 = best quality"]
18269 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
18270 pub quality: i8,
18271}
18272impl ODOMETRY_DATA {
18273 pub const ENCODED_LEN: usize = 233usize;
18274 pub const DEFAULT: Self = Self {
18275 time_usec: 0_u64,
18276 x: 0.0_f32,
18277 y: 0.0_f32,
18278 z: 0.0_f32,
18279 q: [0.0_f32; 4usize],
18280 vx: 0.0_f32,
18281 vy: 0.0_f32,
18282 vz: 0.0_f32,
18283 rollspeed: 0.0_f32,
18284 pitchspeed: 0.0_f32,
18285 yawspeed: 0.0_f32,
18286 pose_covariance: [0.0_f32; 21usize],
18287 velocity_covariance: [0.0_f32; 21usize],
18288 frame_id: MavFrame::DEFAULT,
18289 child_frame_id: MavFrame::DEFAULT,
18290 reset_counter: 0_u8,
18291 estimator_type: MavEstimatorType::DEFAULT,
18292 quality: 0_i8,
18293 };
18294 #[cfg(feature = "arbitrary")]
18295 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
18296 use arbitrary::{Arbitrary, Unstructured};
18297 let mut buf = [0u8; 1024];
18298 rng.fill_bytes(&mut buf);
18299 let mut unstructured = Unstructured::new(&buf);
18300 Self::arbitrary(&mut unstructured).unwrap_or_default()
18301 }
18302}
18303impl Default for ODOMETRY_DATA {
18304 fn default() -> Self {
18305 Self::DEFAULT.clone()
18306 }
18307}
18308impl MessageData for ODOMETRY_DATA {
18309 type Message = MavMessage;
18310 const ID: u32 = 331u32;
18311 const NAME: &'static str = "ODOMETRY";
18312 const EXTRA_CRC: u8 = 91u8;
18313 const ENCODED_LEN: usize = 233usize;
18314 fn deser(
18315 _version: MavlinkVersion,
18316 __input: &[u8],
18317 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18318 let avail_len = __input.len();
18319 let mut payload_buf = [0; Self::ENCODED_LEN];
18320 let mut buf = if avail_len < Self::ENCODED_LEN {
18321 payload_buf[0..avail_len].copy_from_slice(__input);
18322 Bytes::new(&payload_buf)
18323 } else {
18324 Bytes::new(__input)
18325 };
18326 let mut __struct = Self::default();
18327 __struct.time_usec = buf.get_u64_le();
18328 __struct.x = buf.get_f32_le();
18329 __struct.y = buf.get_f32_le();
18330 __struct.z = buf.get_f32_le();
18331 for v in &mut __struct.q {
18332 let val = buf.get_f32_le();
18333 *v = val;
18334 }
18335 __struct.vx = buf.get_f32_le();
18336 __struct.vy = buf.get_f32_le();
18337 __struct.vz = buf.get_f32_le();
18338 __struct.rollspeed = buf.get_f32_le();
18339 __struct.pitchspeed = buf.get_f32_le();
18340 __struct.yawspeed = buf.get_f32_le();
18341 for v in &mut __struct.pose_covariance {
18342 let val = buf.get_f32_le();
18343 *v = val;
18344 }
18345 for v in &mut __struct.velocity_covariance {
18346 let val = buf.get_f32_le();
18347 *v = val;
18348 }
18349 let tmp = buf.get_u8();
18350 __struct.frame_id =
18351 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
18352 enum_type: "MavFrame",
18353 value: tmp as u32,
18354 })?;
18355 let tmp = buf.get_u8();
18356 __struct.child_frame_id =
18357 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
18358 enum_type: "MavFrame",
18359 value: tmp as u32,
18360 })?;
18361 __struct.reset_counter = buf.get_u8();
18362 let tmp = buf.get_u8();
18363 __struct.estimator_type =
18364 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
18365 enum_type: "MavEstimatorType",
18366 value: tmp as u32,
18367 })?;
18368 __struct.quality = buf.get_i8();
18369 Ok(__struct)
18370 }
18371 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18372 let mut __tmp = BytesMut::new(bytes);
18373 #[allow(clippy::absurd_extreme_comparisons)]
18374 #[allow(unused_comparisons)]
18375 if __tmp.remaining() < Self::ENCODED_LEN {
18376 panic!(
18377 "buffer is too small (need {} bytes, but got {})",
18378 Self::ENCODED_LEN,
18379 __tmp.remaining(),
18380 )
18381 }
18382 __tmp.put_u64_le(self.time_usec);
18383 __tmp.put_f32_le(self.x);
18384 __tmp.put_f32_le(self.y);
18385 __tmp.put_f32_le(self.z);
18386 for val in &self.q {
18387 __tmp.put_f32_le(*val);
18388 }
18389 __tmp.put_f32_le(self.vx);
18390 __tmp.put_f32_le(self.vy);
18391 __tmp.put_f32_le(self.vz);
18392 __tmp.put_f32_le(self.rollspeed);
18393 __tmp.put_f32_le(self.pitchspeed);
18394 __tmp.put_f32_le(self.yawspeed);
18395 for val in &self.pose_covariance {
18396 __tmp.put_f32_le(*val);
18397 }
18398 for val in &self.velocity_covariance {
18399 __tmp.put_f32_le(*val);
18400 }
18401 __tmp.put_u8(self.frame_id as u8);
18402 __tmp.put_u8(self.child_frame_id as u8);
18403 __tmp.put_u8(self.reset_counter);
18404 __tmp.put_u8(self.estimator_type as u8);
18405 __tmp.put_i8(self.quality);
18406 if matches!(version, MavlinkVersion::V2) {
18407 let len = __tmp.len();
18408 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18409 } else {
18410 __tmp.len()
18411 }
18412 }
18413}
18414#[doc = "id: 269"]
18415#[doc = "Information about video stream. It may be requested using MAV_CMD_REQUEST_MESSAGE, where param2 indicates the video stream id: 0 for all streams, 1 for first, 2 for second, etc."]
18416#[derive(Debug, Clone, PartialEq)]
18417#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18418#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18419pub struct VIDEO_STREAM_INFORMATION_DATA {
18420 #[doc = "Frame rate."]
18421 pub framerate: f32,
18422 #[doc = "Bit rate."]
18423 pub bitrate: u32,
18424 #[doc = "Bitmap of stream status flags."]
18425 pub flags: VideoStreamStatusFlags,
18426 #[doc = "Horizontal resolution."]
18427 pub resolution_h: u16,
18428 #[doc = "Vertical resolution."]
18429 pub resolution_v: u16,
18430 #[doc = "Video image rotation clockwise."]
18431 pub rotation: u16,
18432 #[doc = "Horizontal Field of view."]
18433 pub hfov: u16,
18434 #[doc = "Video Stream ID (1 for first, 2 for second, etc.)"]
18435 pub stream_id: u8,
18436 #[doc = "Number of streams available."]
18437 pub count: u8,
18438 #[doc = "Type of stream."]
18439 pub mavtype: VideoStreamType,
18440 #[doc = "Stream name."]
18441 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
18442 pub name: [u8; 32],
18443 #[doc = "Video stream URI (TCP or RTSP URI ground station should connect to) or port number (UDP port ground station should listen to)."]
18444 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
18445 pub uri: [u8; 160],
18446 #[doc = "Encoding of stream."]
18447 #[cfg_attr(feature = "serde", serde(default))]
18448 pub encoding: VideoStreamEncoding,
18449 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
18450 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
18451 pub camera_device_id: u8,
18452}
18453impl VIDEO_STREAM_INFORMATION_DATA {
18454 pub const ENCODED_LEN: usize = 215usize;
18455 pub const DEFAULT: Self = Self {
18456 framerate: 0.0_f32,
18457 bitrate: 0_u32,
18458 flags: VideoStreamStatusFlags::DEFAULT,
18459 resolution_h: 0_u16,
18460 resolution_v: 0_u16,
18461 rotation: 0_u16,
18462 hfov: 0_u16,
18463 stream_id: 0_u8,
18464 count: 0_u8,
18465 mavtype: VideoStreamType::DEFAULT,
18466 name: [0_u8; 32usize],
18467 uri: [0_u8; 160usize],
18468 encoding: VideoStreamEncoding::DEFAULT,
18469 camera_device_id: 0_u8,
18470 };
18471 #[cfg(feature = "arbitrary")]
18472 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
18473 use arbitrary::{Arbitrary, Unstructured};
18474 let mut buf = [0u8; 1024];
18475 rng.fill_bytes(&mut buf);
18476 let mut unstructured = Unstructured::new(&buf);
18477 Self::arbitrary(&mut unstructured).unwrap_or_default()
18478 }
18479}
18480impl Default for VIDEO_STREAM_INFORMATION_DATA {
18481 fn default() -> Self {
18482 Self::DEFAULT.clone()
18483 }
18484}
18485impl MessageData for VIDEO_STREAM_INFORMATION_DATA {
18486 type Message = MavMessage;
18487 const ID: u32 = 269u32;
18488 const NAME: &'static str = "VIDEO_STREAM_INFORMATION";
18489 const EXTRA_CRC: u8 = 109u8;
18490 const ENCODED_LEN: usize = 215usize;
18491 fn deser(
18492 _version: MavlinkVersion,
18493 __input: &[u8],
18494 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18495 let avail_len = __input.len();
18496 let mut payload_buf = [0; Self::ENCODED_LEN];
18497 let mut buf = if avail_len < Self::ENCODED_LEN {
18498 payload_buf[0..avail_len].copy_from_slice(__input);
18499 Bytes::new(&payload_buf)
18500 } else {
18501 Bytes::new(__input)
18502 };
18503 let mut __struct = Self::default();
18504 __struct.framerate = buf.get_f32_le();
18505 __struct.bitrate = buf.get_u32_le();
18506 let tmp = buf.get_u16_le();
18507 __struct.flags = VideoStreamStatusFlags::from_bits(
18508 tmp & VideoStreamStatusFlags::all().bits(),
18509 )
18510 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
18511 flag_type: "VideoStreamStatusFlags",
18512 value: tmp as u32,
18513 })?;
18514 __struct.resolution_h = buf.get_u16_le();
18515 __struct.resolution_v = buf.get_u16_le();
18516 __struct.rotation = buf.get_u16_le();
18517 __struct.hfov = buf.get_u16_le();
18518 __struct.stream_id = buf.get_u8();
18519 __struct.count = buf.get_u8();
18520 let tmp = buf.get_u8();
18521 __struct.mavtype =
18522 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
18523 enum_type: "VideoStreamType",
18524 value: tmp as u32,
18525 })?;
18526 for v in &mut __struct.name {
18527 let val = buf.get_u8();
18528 *v = val;
18529 }
18530 for v in &mut __struct.uri {
18531 let val = buf.get_u8();
18532 *v = val;
18533 }
18534 let tmp = buf.get_u8();
18535 __struct.encoding =
18536 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
18537 enum_type: "VideoStreamEncoding",
18538 value: tmp as u32,
18539 })?;
18540 __struct.camera_device_id = buf.get_u8();
18541 Ok(__struct)
18542 }
18543 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18544 let mut __tmp = BytesMut::new(bytes);
18545 #[allow(clippy::absurd_extreme_comparisons)]
18546 #[allow(unused_comparisons)]
18547 if __tmp.remaining() < Self::ENCODED_LEN {
18548 panic!(
18549 "buffer is too small (need {} bytes, but got {})",
18550 Self::ENCODED_LEN,
18551 __tmp.remaining(),
18552 )
18553 }
18554 __tmp.put_f32_le(self.framerate);
18555 __tmp.put_u32_le(self.bitrate);
18556 __tmp.put_u16_le(self.flags.bits());
18557 __tmp.put_u16_le(self.resolution_h);
18558 __tmp.put_u16_le(self.resolution_v);
18559 __tmp.put_u16_le(self.rotation);
18560 __tmp.put_u16_le(self.hfov);
18561 __tmp.put_u8(self.stream_id);
18562 __tmp.put_u8(self.count);
18563 __tmp.put_u8(self.mavtype as u8);
18564 for val in &self.name {
18565 __tmp.put_u8(*val);
18566 }
18567 for val in &self.uri {
18568 __tmp.put_u8(*val);
18569 }
18570 __tmp.put_u8(self.encoding as u8);
18571 __tmp.put_u8(self.camera_device_id);
18572 if matches!(version, MavlinkVersion::V2) {
18573 let len = __tmp.len();
18574 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18575 } else {
18576 __tmp.len()
18577 }
18578 }
18579}
18580#[doc = "id: 276"]
18581#[doc = "Camera tracking status, sent while in active tracking. Use MAV_CMD_SET_MESSAGE_INTERVAL to define message interval."]
18582#[derive(Debug, Clone, PartialEq)]
18583#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18584#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18585pub struct CAMERA_TRACKING_GEO_STATUS_DATA {
18586 #[doc = "Latitude of tracked object"]
18587 pub lat: i32,
18588 #[doc = "Longitude of tracked object"]
18589 pub lon: i32,
18590 #[doc = "Altitude of tracked object(AMSL, WGS84)"]
18591 pub alt: f32,
18592 #[doc = "Horizontal accuracy. NAN if unknown"]
18593 pub h_acc: f32,
18594 #[doc = "Vertical accuracy. NAN if unknown"]
18595 pub v_acc: f32,
18596 #[doc = "North velocity of tracked object. NAN if unknown"]
18597 pub vel_n: f32,
18598 #[doc = "East velocity of tracked object. NAN if unknown"]
18599 pub vel_e: f32,
18600 #[doc = "Down velocity of tracked object. NAN if unknown"]
18601 pub vel_d: f32,
18602 #[doc = "Velocity accuracy. NAN if unknown"]
18603 pub vel_acc: f32,
18604 #[doc = "Distance between camera and tracked object. NAN if unknown"]
18605 pub dist: f32,
18606 #[doc = "Heading in radians, in NED. NAN if unknown"]
18607 pub hdg: f32,
18608 #[doc = "Accuracy of heading, in NED. NAN if unknown"]
18609 pub hdg_acc: f32,
18610 #[doc = "Current tracking status"]
18611 pub tracking_status: CameraTrackingStatusFlags,
18612 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
18613 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
18614 pub camera_device_id: u8,
18615}
18616impl CAMERA_TRACKING_GEO_STATUS_DATA {
18617 pub const ENCODED_LEN: usize = 50usize;
18618 pub const DEFAULT: Self = Self {
18619 lat: 0_i32,
18620 lon: 0_i32,
18621 alt: 0.0_f32,
18622 h_acc: 0.0_f32,
18623 v_acc: 0.0_f32,
18624 vel_n: 0.0_f32,
18625 vel_e: 0.0_f32,
18626 vel_d: 0.0_f32,
18627 vel_acc: 0.0_f32,
18628 dist: 0.0_f32,
18629 hdg: 0.0_f32,
18630 hdg_acc: 0.0_f32,
18631 tracking_status: CameraTrackingStatusFlags::DEFAULT,
18632 camera_device_id: 0_u8,
18633 };
18634 #[cfg(feature = "arbitrary")]
18635 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
18636 use arbitrary::{Arbitrary, Unstructured};
18637 let mut buf = [0u8; 1024];
18638 rng.fill_bytes(&mut buf);
18639 let mut unstructured = Unstructured::new(&buf);
18640 Self::arbitrary(&mut unstructured).unwrap_or_default()
18641 }
18642}
18643impl Default for CAMERA_TRACKING_GEO_STATUS_DATA {
18644 fn default() -> Self {
18645 Self::DEFAULT.clone()
18646 }
18647}
18648impl MessageData for CAMERA_TRACKING_GEO_STATUS_DATA {
18649 type Message = MavMessage;
18650 const ID: u32 = 276u32;
18651 const NAME: &'static str = "CAMERA_TRACKING_GEO_STATUS";
18652 const EXTRA_CRC: u8 = 18u8;
18653 const ENCODED_LEN: usize = 50usize;
18654 fn deser(
18655 _version: MavlinkVersion,
18656 __input: &[u8],
18657 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18658 let avail_len = __input.len();
18659 let mut payload_buf = [0; Self::ENCODED_LEN];
18660 let mut buf = if avail_len < Self::ENCODED_LEN {
18661 payload_buf[0..avail_len].copy_from_slice(__input);
18662 Bytes::new(&payload_buf)
18663 } else {
18664 Bytes::new(__input)
18665 };
18666 let mut __struct = Self::default();
18667 __struct.lat = buf.get_i32_le();
18668 __struct.lon = buf.get_i32_le();
18669 __struct.alt = buf.get_f32_le();
18670 __struct.h_acc = buf.get_f32_le();
18671 __struct.v_acc = buf.get_f32_le();
18672 __struct.vel_n = buf.get_f32_le();
18673 __struct.vel_e = buf.get_f32_le();
18674 __struct.vel_d = buf.get_f32_le();
18675 __struct.vel_acc = buf.get_f32_le();
18676 __struct.dist = buf.get_f32_le();
18677 __struct.hdg = buf.get_f32_le();
18678 __struct.hdg_acc = buf.get_f32_le();
18679 let tmp = buf.get_u8();
18680 __struct.tracking_status =
18681 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
18682 enum_type: "CameraTrackingStatusFlags",
18683 value: tmp as u32,
18684 })?;
18685 __struct.camera_device_id = buf.get_u8();
18686 Ok(__struct)
18687 }
18688 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18689 let mut __tmp = BytesMut::new(bytes);
18690 #[allow(clippy::absurd_extreme_comparisons)]
18691 #[allow(unused_comparisons)]
18692 if __tmp.remaining() < Self::ENCODED_LEN {
18693 panic!(
18694 "buffer is too small (need {} bytes, but got {})",
18695 Self::ENCODED_LEN,
18696 __tmp.remaining(),
18697 )
18698 }
18699 __tmp.put_i32_le(self.lat);
18700 __tmp.put_i32_le(self.lon);
18701 __tmp.put_f32_le(self.alt);
18702 __tmp.put_f32_le(self.h_acc);
18703 __tmp.put_f32_le(self.v_acc);
18704 __tmp.put_f32_le(self.vel_n);
18705 __tmp.put_f32_le(self.vel_e);
18706 __tmp.put_f32_le(self.vel_d);
18707 __tmp.put_f32_le(self.vel_acc);
18708 __tmp.put_f32_le(self.dist);
18709 __tmp.put_f32_le(self.hdg);
18710 __tmp.put_f32_le(self.hdg_acc);
18711 __tmp.put_u8(self.tracking_status as u8);
18712 __tmp.put_u8(self.camera_device_id);
18713 if matches!(version, MavlinkVersion::V2) {
18714 let len = __tmp.len();
18715 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18716 } else {
18717 __tmp.len()
18718 }
18719 }
18720}
18721#[doc = "id: 397"]
18722#[doc = "Component metadata message, which may be requested using MAV_CMD_REQUEST_MESSAGE. This contains the MAVLink FTP URI and CRC for the component's general metadata file. The file must be hosted on the component, and may be xz compressed. The file CRC can be used for file caching. The general metadata file can be read to get the locations of other metadata files (COMP_METADATA_TYPE) and translations, which may be hosted either on the vehicle or the internet. For more information see: <https://mavlink.io/en/services/component_information.html>. Note: Camera components should use CAMERA_INFORMATION instead, and autopilots may use both this message and AUTOPILOT_VERSION."]
18723#[derive(Debug, Clone, PartialEq)]
18724#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18725#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18726pub struct COMPONENT_METADATA_DATA {
18727 #[doc = "Timestamp (time since system boot)."]
18728 pub time_boot_ms: u32,
18729 #[doc = "CRC32 of the general metadata file."]
18730 pub file_crc: u32,
18731 #[doc = "MAVLink FTP URI for the general metadata file (COMP_METADATA_TYPE_GENERAL), which may be compressed with xz. The file contains general component metadata, and may contain URI links for additional metadata (see COMP_METADATA_TYPE). The information is static from boot, and may be generated at compile time. The string needs to be zero terminated."]
18732 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
18733 pub uri: [u8; 100],
18734}
18735impl COMPONENT_METADATA_DATA {
18736 pub const ENCODED_LEN: usize = 108usize;
18737 pub const DEFAULT: Self = Self {
18738 time_boot_ms: 0_u32,
18739 file_crc: 0_u32,
18740 uri: [0_u8; 100usize],
18741 };
18742 #[cfg(feature = "arbitrary")]
18743 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
18744 use arbitrary::{Arbitrary, Unstructured};
18745 let mut buf = [0u8; 1024];
18746 rng.fill_bytes(&mut buf);
18747 let mut unstructured = Unstructured::new(&buf);
18748 Self::arbitrary(&mut unstructured).unwrap_or_default()
18749 }
18750}
18751impl Default for COMPONENT_METADATA_DATA {
18752 fn default() -> Self {
18753 Self::DEFAULT.clone()
18754 }
18755}
18756impl MessageData for COMPONENT_METADATA_DATA {
18757 type Message = MavMessage;
18758 const ID: u32 = 397u32;
18759 const NAME: &'static str = "COMPONENT_METADATA";
18760 const EXTRA_CRC: u8 = 182u8;
18761 const ENCODED_LEN: usize = 108usize;
18762 fn deser(
18763 _version: MavlinkVersion,
18764 __input: &[u8],
18765 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18766 let avail_len = __input.len();
18767 let mut payload_buf = [0; Self::ENCODED_LEN];
18768 let mut buf = if avail_len < Self::ENCODED_LEN {
18769 payload_buf[0..avail_len].copy_from_slice(__input);
18770 Bytes::new(&payload_buf)
18771 } else {
18772 Bytes::new(__input)
18773 };
18774 let mut __struct = Self::default();
18775 __struct.time_boot_ms = buf.get_u32_le();
18776 __struct.file_crc = buf.get_u32_le();
18777 for v in &mut __struct.uri {
18778 let val = buf.get_u8();
18779 *v = val;
18780 }
18781 Ok(__struct)
18782 }
18783 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18784 let mut __tmp = BytesMut::new(bytes);
18785 #[allow(clippy::absurd_extreme_comparisons)]
18786 #[allow(unused_comparisons)]
18787 if __tmp.remaining() < Self::ENCODED_LEN {
18788 panic!(
18789 "buffer is too small (need {} bytes, but got {})",
18790 Self::ENCODED_LEN,
18791 __tmp.remaining(),
18792 )
18793 }
18794 __tmp.put_u32_le(self.time_boot_ms);
18795 __tmp.put_u32_le(self.file_crc);
18796 for val in &self.uri {
18797 __tmp.put_u8(*val);
18798 }
18799 if matches!(version, MavlinkVersion::V2) {
18800 let len = __tmp.len();
18801 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18802 } else {
18803 __tmp.len()
18804 }
18805 }
18806}
18807#[doc = "id: 65"]
18808#[doc = "The PPM values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. A value of UINT16_MAX implies the channel is unused. Individual receivers/transmitters might violate this specification."]
18809#[derive(Debug, Clone, PartialEq)]
18810#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18811#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18812pub struct RC_CHANNELS_DATA {
18813 #[doc = "Timestamp (time since system boot)."]
18814 pub time_boot_ms: u32,
18815 #[doc = "RC channel 1 value."]
18816 pub chan1_raw: u16,
18817 #[doc = "RC channel 2 value."]
18818 pub chan2_raw: u16,
18819 #[doc = "RC channel 3 value."]
18820 pub chan3_raw: u16,
18821 #[doc = "RC channel 4 value."]
18822 pub chan4_raw: u16,
18823 #[doc = "RC channel 5 value."]
18824 pub chan5_raw: u16,
18825 #[doc = "RC channel 6 value."]
18826 pub chan6_raw: u16,
18827 #[doc = "RC channel 7 value."]
18828 pub chan7_raw: u16,
18829 #[doc = "RC channel 8 value."]
18830 pub chan8_raw: u16,
18831 #[doc = "RC channel 9 value."]
18832 pub chan9_raw: u16,
18833 #[doc = "RC channel 10 value."]
18834 pub chan10_raw: u16,
18835 #[doc = "RC channel 11 value."]
18836 pub chan11_raw: u16,
18837 #[doc = "RC channel 12 value."]
18838 pub chan12_raw: u16,
18839 #[doc = "RC channel 13 value."]
18840 pub chan13_raw: u16,
18841 #[doc = "RC channel 14 value."]
18842 pub chan14_raw: u16,
18843 #[doc = "RC channel 15 value."]
18844 pub chan15_raw: u16,
18845 #[doc = "RC channel 16 value."]
18846 pub chan16_raw: u16,
18847 #[doc = "RC channel 17 value."]
18848 pub chan17_raw: u16,
18849 #[doc = "RC channel 18 value."]
18850 pub chan18_raw: u16,
18851 #[doc = "Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available."]
18852 pub chancount: u8,
18853 #[doc = "Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown."]
18854 pub rssi: u8,
18855}
18856impl RC_CHANNELS_DATA {
18857 pub const ENCODED_LEN: usize = 42usize;
18858 pub const DEFAULT: Self = Self {
18859 time_boot_ms: 0_u32,
18860 chan1_raw: 0_u16,
18861 chan2_raw: 0_u16,
18862 chan3_raw: 0_u16,
18863 chan4_raw: 0_u16,
18864 chan5_raw: 0_u16,
18865 chan6_raw: 0_u16,
18866 chan7_raw: 0_u16,
18867 chan8_raw: 0_u16,
18868 chan9_raw: 0_u16,
18869 chan10_raw: 0_u16,
18870 chan11_raw: 0_u16,
18871 chan12_raw: 0_u16,
18872 chan13_raw: 0_u16,
18873 chan14_raw: 0_u16,
18874 chan15_raw: 0_u16,
18875 chan16_raw: 0_u16,
18876 chan17_raw: 0_u16,
18877 chan18_raw: 0_u16,
18878 chancount: 0_u8,
18879 rssi: 0_u8,
18880 };
18881 #[cfg(feature = "arbitrary")]
18882 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
18883 use arbitrary::{Arbitrary, Unstructured};
18884 let mut buf = [0u8; 1024];
18885 rng.fill_bytes(&mut buf);
18886 let mut unstructured = Unstructured::new(&buf);
18887 Self::arbitrary(&mut unstructured).unwrap_or_default()
18888 }
18889}
18890impl Default for RC_CHANNELS_DATA {
18891 fn default() -> Self {
18892 Self::DEFAULT.clone()
18893 }
18894}
18895impl MessageData for RC_CHANNELS_DATA {
18896 type Message = MavMessage;
18897 const ID: u32 = 65u32;
18898 const NAME: &'static str = "RC_CHANNELS";
18899 const EXTRA_CRC: u8 = 118u8;
18900 const ENCODED_LEN: usize = 42usize;
18901 fn deser(
18902 _version: MavlinkVersion,
18903 __input: &[u8],
18904 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18905 let avail_len = __input.len();
18906 let mut payload_buf = [0; Self::ENCODED_LEN];
18907 let mut buf = if avail_len < Self::ENCODED_LEN {
18908 payload_buf[0..avail_len].copy_from_slice(__input);
18909 Bytes::new(&payload_buf)
18910 } else {
18911 Bytes::new(__input)
18912 };
18913 let mut __struct = Self::default();
18914 __struct.time_boot_ms = buf.get_u32_le();
18915 __struct.chan1_raw = buf.get_u16_le();
18916 __struct.chan2_raw = buf.get_u16_le();
18917 __struct.chan3_raw = buf.get_u16_le();
18918 __struct.chan4_raw = buf.get_u16_le();
18919 __struct.chan5_raw = buf.get_u16_le();
18920 __struct.chan6_raw = buf.get_u16_le();
18921 __struct.chan7_raw = buf.get_u16_le();
18922 __struct.chan8_raw = buf.get_u16_le();
18923 __struct.chan9_raw = buf.get_u16_le();
18924 __struct.chan10_raw = buf.get_u16_le();
18925 __struct.chan11_raw = buf.get_u16_le();
18926 __struct.chan12_raw = buf.get_u16_le();
18927 __struct.chan13_raw = buf.get_u16_le();
18928 __struct.chan14_raw = buf.get_u16_le();
18929 __struct.chan15_raw = buf.get_u16_le();
18930 __struct.chan16_raw = buf.get_u16_le();
18931 __struct.chan17_raw = buf.get_u16_le();
18932 __struct.chan18_raw = buf.get_u16_le();
18933 __struct.chancount = buf.get_u8();
18934 __struct.rssi = buf.get_u8();
18935 Ok(__struct)
18936 }
18937 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18938 let mut __tmp = BytesMut::new(bytes);
18939 #[allow(clippy::absurd_extreme_comparisons)]
18940 #[allow(unused_comparisons)]
18941 if __tmp.remaining() < Self::ENCODED_LEN {
18942 panic!(
18943 "buffer is too small (need {} bytes, but got {})",
18944 Self::ENCODED_LEN,
18945 __tmp.remaining(),
18946 )
18947 }
18948 __tmp.put_u32_le(self.time_boot_ms);
18949 __tmp.put_u16_le(self.chan1_raw);
18950 __tmp.put_u16_le(self.chan2_raw);
18951 __tmp.put_u16_le(self.chan3_raw);
18952 __tmp.put_u16_le(self.chan4_raw);
18953 __tmp.put_u16_le(self.chan5_raw);
18954 __tmp.put_u16_le(self.chan6_raw);
18955 __tmp.put_u16_le(self.chan7_raw);
18956 __tmp.put_u16_le(self.chan8_raw);
18957 __tmp.put_u16_le(self.chan9_raw);
18958 __tmp.put_u16_le(self.chan10_raw);
18959 __tmp.put_u16_le(self.chan11_raw);
18960 __tmp.put_u16_le(self.chan12_raw);
18961 __tmp.put_u16_le(self.chan13_raw);
18962 __tmp.put_u16_le(self.chan14_raw);
18963 __tmp.put_u16_le(self.chan15_raw);
18964 __tmp.put_u16_le(self.chan16_raw);
18965 __tmp.put_u16_le(self.chan17_raw);
18966 __tmp.put_u16_le(self.chan18_raw);
18967 __tmp.put_u8(self.chancount);
18968 __tmp.put_u8(self.rssi);
18969 if matches!(version, MavlinkVersion::V2) {
18970 let len = __tmp.len();
18971 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18972 } else {
18973 __tmp.len()
18974 }
18975 }
18976}
18977#[doc = "id: 83"]
18978#[doc = "Reports the current commanded attitude of the vehicle as specified by the autopilot. This should match the commands sent in a SET_ATTITUDE_TARGET message if the vehicle is being controlled this way."]
18979#[derive(Debug, Clone, PartialEq)]
18980#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18981#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18982pub struct ATTITUDE_TARGET_DATA {
18983 #[doc = "Timestamp (time since system boot)."]
18984 pub time_boot_ms: u32,
18985 #[doc = "Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)"]
18986 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
18987 pub q: [f32; 4],
18988 #[doc = "Body roll rate"]
18989 pub body_roll_rate: f32,
18990 #[doc = "Body pitch rate"]
18991 pub body_pitch_rate: f32,
18992 #[doc = "Body yaw rate"]
18993 pub body_yaw_rate: f32,
18994 #[doc = "Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)"]
18995 pub thrust: f32,
18996 #[doc = "Bitmap to indicate which dimensions should be ignored by the vehicle."]
18997 pub type_mask: AttitudeTargetTypemask,
18998}
18999impl ATTITUDE_TARGET_DATA {
19000 pub const ENCODED_LEN: usize = 37usize;
19001 pub const DEFAULT: Self = Self {
19002 time_boot_ms: 0_u32,
19003 q: [0.0_f32; 4usize],
19004 body_roll_rate: 0.0_f32,
19005 body_pitch_rate: 0.0_f32,
19006 body_yaw_rate: 0.0_f32,
19007 thrust: 0.0_f32,
19008 type_mask: AttitudeTargetTypemask::DEFAULT,
19009 };
19010 #[cfg(feature = "arbitrary")]
19011 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19012 use arbitrary::{Arbitrary, Unstructured};
19013 let mut buf = [0u8; 1024];
19014 rng.fill_bytes(&mut buf);
19015 let mut unstructured = Unstructured::new(&buf);
19016 Self::arbitrary(&mut unstructured).unwrap_or_default()
19017 }
19018}
19019impl Default for ATTITUDE_TARGET_DATA {
19020 fn default() -> Self {
19021 Self::DEFAULT.clone()
19022 }
19023}
19024impl MessageData for ATTITUDE_TARGET_DATA {
19025 type Message = MavMessage;
19026 const ID: u32 = 83u32;
19027 const NAME: &'static str = "ATTITUDE_TARGET";
19028 const EXTRA_CRC: u8 = 22u8;
19029 const ENCODED_LEN: usize = 37usize;
19030 fn deser(
19031 _version: MavlinkVersion,
19032 __input: &[u8],
19033 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19034 let avail_len = __input.len();
19035 let mut payload_buf = [0; Self::ENCODED_LEN];
19036 let mut buf = if avail_len < Self::ENCODED_LEN {
19037 payload_buf[0..avail_len].copy_from_slice(__input);
19038 Bytes::new(&payload_buf)
19039 } else {
19040 Bytes::new(__input)
19041 };
19042 let mut __struct = Self::default();
19043 __struct.time_boot_ms = buf.get_u32_le();
19044 for v in &mut __struct.q {
19045 let val = buf.get_f32_le();
19046 *v = val;
19047 }
19048 __struct.body_roll_rate = buf.get_f32_le();
19049 __struct.body_pitch_rate = buf.get_f32_le();
19050 __struct.body_yaw_rate = buf.get_f32_le();
19051 __struct.thrust = buf.get_f32_le();
19052 let tmp = buf.get_u8();
19053 __struct.type_mask = AttitudeTargetTypemask::from_bits(
19054 tmp & AttitudeTargetTypemask::all().bits(),
19055 )
19056 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
19057 flag_type: "AttitudeTargetTypemask",
19058 value: tmp as u32,
19059 })?;
19060 Ok(__struct)
19061 }
19062 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19063 let mut __tmp = BytesMut::new(bytes);
19064 #[allow(clippy::absurd_extreme_comparisons)]
19065 #[allow(unused_comparisons)]
19066 if __tmp.remaining() < Self::ENCODED_LEN {
19067 panic!(
19068 "buffer is too small (need {} bytes, but got {})",
19069 Self::ENCODED_LEN,
19070 __tmp.remaining(),
19071 )
19072 }
19073 __tmp.put_u32_le(self.time_boot_ms);
19074 for val in &self.q {
19075 __tmp.put_f32_le(*val);
19076 }
19077 __tmp.put_f32_le(self.body_roll_rate);
19078 __tmp.put_f32_le(self.body_pitch_rate);
19079 __tmp.put_f32_le(self.body_yaw_rate);
19080 __tmp.put_f32_le(self.thrust);
19081 __tmp.put_u8(self.type_mask.bits());
19082 if matches!(version, MavlinkVersion::V2) {
19083 let len = __tmp.len();
19084 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19085 } else {
19086 __tmp.len()
19087 }
19088 }
19089}
19090#[doc = "id: 275"]
19091#[doc = "Camera tracking status, sent while in active tracking. Use MAV_CMD_SET_MESSAGE_INTERVAL to define message interval."]
19092#[derive(Debug, Clone, PartialEq)]
19093#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19094#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19095pub struct CAMERA_TRACKING_IMAGE_STATUS_DATA {
19096 #[doc = "Current tracked point x value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is left, 1 is right), NAN if unknown"]
19097 pub point_x: f32,
19098 #[doc = "Current tracked point y value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown"]
19099 pub point_y: f32,
19100 #[doc = "Current tracked radius if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is image left, 1 is image right), NAN if unknown"]
19101 pub radius: f32,
19102 #[doc = "Current tracked rectangle top x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown"]
19103 pub rec_top_x: f32,
19104 #[doc = "Current tracked rectangle top y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown"]
19105 pub rec_top_y: f32,
19106 #[doc = "Current tracked rectangle bottom x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown"]
19107 pub rec_bottom_x: f32,
19108 #[doc = "Current tracked rectangle bottom y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown"]
19109 pub rec_bottom_y: f32,
19110 #[doc = "Current tracking status"]
19111 pub tracking_status: CameraTrackingStatusFlags,
19112 #[doc = "Current tracking mode"]
19113 pub tracking_mode: CameraTrackingMode,
19114 #[doc = "Defines location of target data"]
19115 pub target_data: CameraTrackingTargetData,
19116 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
19117 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
19118 pub camera_device_id: u8,
19119}
19120impl CAMERA_TRACKING_IMAGE_STATUS_DATA {
19121 pub const ENCODED_LEN: usize = 32usize;
19122 pub const DEFAULT: Self = Self {
19123 point_x: 0.0_f32,
19124 point_y: 0.0_f32,
19125 radius: 0.0_f32,
19126 rec_top_x: 0.0_f32,
19127 rec_top_y: 0.0_f32,
19128 rec_bottom_x: 0.0_f32,
19129 rec_bottom_y: 0.0_f32,
19130 tracking_status: CameraTrackingStatusFlags::DEFAULT,
19131 tracking_mode: CameraTrackingMode::DEFAULT,
19132 target_data: CameraTrackingTargetData::DEFAULT,
19133 camera_device_id: 0_u8,
19134 };
19135 #[cfg(feature = "arbitrary")]
19136 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19137 use arbitrary::{Arbitrary, Unstructured};
19138 let mut buf = [0u8; 1024];
19139 rng.fill_bytes(&mut buf);
19140 let mut unstructured = Unstructured::new(&buf);
19141 Self::arbitrary(&mut unstructured).unwrap_or_default()
19142 }
19143}
19144impl Default for CAMERA_TRACKING_IMAGE_STATUS_DATA {
19145 fn default() -> Self {
19146 Self::DEFAULT.clone()
19147 }
19148}
19149impl MessageData for CAMERA_TRACKING_IMAGE_STATUS_DATA {
19150 type Message = MavMessage;
19151 const ID: u32 = 275u32;
19152 const NAME: &'static str = "CAMERA_TRACKING_IMAGE_STATUS";
19153 const EXTRA_CRC: u8 = 126u8;
19154 const ENCODED_LEN: usize = 32usize;
19155 fn deser(
19156 _version: MavlinkVersion,
19157 __input: &[u8],
19158 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19159 let avail_len = __input.len();
19160 let mut payload_buf = [0; Self::ENCODED_LEN];
19161 let mut buf = if avail_len < Self::ENCODED_LEN {
19162 payload_buf[0..avail_len].copy_from_slice(__input);
19163 Bytes::new(&payload_buf)
19164 } else {
19165 Bytes::new(__input)
19166 };
19167 let mut __struct = Self::default();
19168 __struct.point_x = buf.get_f32_le();
19169 __struct.point_y = buf.get_f32_le();
19170 __struct.radius = buf.get_f32_le();
19171 __struct.rec_top_x = buf.get_f32_le();
19172 __struct.rec_top_y = buf.get_f32_le();
19173 __struct.rec_bottom_x = buf.get_f32_le();
19174 __struct.rec_bottom_y = buf.get_f32_le();
19175 let tmp = buf.get_u8();
19176 __struct.tracking_status =
19177 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
19178 enum_type: "CameraTrackingStatusFlags",
19179 value: tmp as u32,
19180 })?;
19181 let tmp = buf.get_u8();
19182 __struct.tracking_mode =
19183 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
19184 enum_type: "CameraTrackingMode",
19185 value: tmp as u32,
19186 })?;
19187 let tmp = buf.get_u8();
19188 __struct.target_data =
19189 CameraTrackingTargetData::from_bits(tmp & CameraTrackingTargetData::all().bits())
19190 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
19191 flag_type: "CameraTrackingTargetData",
19192 value: tmp as u32,
19193 })?;
19194 __struct.camera_device_id = buf.get_u8();
19195 Ok(__struct)
19196 }
19197 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19198 let mut __tmp = BytesMut::new(bytes);
19199 #[allow(clippy::absurd_extreme_comparisons)]
19200 #[allow(unused_comparisons)]
19201 if __tmp.remaining() < Self::ENCODED_LEN {
19202 panic!(
19203 "buffer is too small (need {} bytes, but got {})",
19204 Self::ENCODED_LEN,
19205 __tmp.remaining(),
19206 )
19207 }
19208 __tmp.put_f32_le(self.point_x);
19209 __tmp.put_f32_le(self.point_y);
19210 __tmp.put_f32_le(self.radius);
19211 __tmp.put_f32_le(self.rec_top_x);
19212 __tmp.put_f32_le(self.rec_top_y);
19213 __tmp.put_f32_le(self.rec_bottom_x);
19214 __tmp.put_f32_le(self.rec_bottom_y);
19215 __tmp.put_u8(self.tracking_status as u8);
19216 __tmp.put_u8(self.tracking_mode as u8);
19217 __tmp.put_u8(self.target_data.bits());
19218 __tmp.put_u8(self.camera_device_id);
19219 if matches!(version, MavlinkVersion::V2) {
19220 let len = __tmp.len();
19221 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19222 } else {
19223 __tmp.len()
19224 }
19225 }
19226}
19227#[doc = "id: 42"]
19228#[doc = "Message that announces the sequence number of the current target mission item (that the system will fly towards/execute when the mission is running). This message should be streamed all the time (nominally at 1Hz). This message should be emitted following a call to MAV_CMD_DO_SET_MISSION_CURRENT or MISSION_SET_CURRENT."]
19229#[derive(Debug, Clone, PartialEq)]
19230#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19231#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19232pub struct MISSION_CURRENT_DATA {
19233 #[doc = "Sequence"]
19234 pub seq: u16,
19235 #[doc = "Total number of mission items on vehicle (on last item, sequence == total). If the autopilot stores its home location as part of the mission this will be excluded from the total. 0: Not supported, UINT16_MAX if no mission is present on the vehicle."]
19236 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
19237 pub total: u16,
19238 #[doc = "Mission state machine state. MISSION_STATE_UNKNOWN if state reporting not supported."]
19239 #[cfg_attr(feature = "serde", serde(default))]
19240 pub mission_state: MissionState,
19241 #[doc = "Vehicle is in a mode that can execute mission items or suspended. 0: Unknown, 1: In mission mode, 2: Suspended (not in mission mode)."]
19242 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
19243 pub mission_mode: u8,
19244 #[doc = "Id of current on-vehicle mission plan, or 0 if IDs are not supported or there is no mission loaded. GCS can use this to track changes to the mission plan type. The same value is returned on mission upload (in the MISSION_ACK)."]
19245 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
19246 pub mission_id: u32,
19247 #[doc = "Id of current on-vehicle fence plan, or 0 if IDs are not supported or there is no fence loaded. GCS can use this to track changes to the fence plan type. The same value is returned on fence upload (in the MISSION_ACK)."]
19248 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
19249 pub fence_id: u32,
19250 #[doc = "Id of current on-vehicle rally point plan, or 0 if IDs are not supported or there are no rally points loaded. GCS can use this to track changes to the rally point plan type. The same value is returned on rally point upload (in the MISSION_ACK)."]
19251 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
19252 pub rally_points_id: u32,
19253}
19254impl MISSION_CURRENT_DATA {
19255 pub const ENCODED_LEN: usize = 18usize;
19256 pub const DEFAULT: Self = Self {
19257 seq: 0_u16,
19258 total: 0_u16,
19259 mission_state: MissionState::DEFAULT,
19260 mission_mode: 0_u8,
19261 mission_id: 0_u32,
19262 fence_id: 0_u32,
19263 rally_points_id: 0_u32,
19264 };
19265 #[cfg(feature = "arbitrary")]
19266 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19267 use arbitrary::{Arbitrary, Unstructured};
19268 let mut buf = [0u8; 1024];
19269 rng.fill_bytes(&mut buf);
19270 let mut unstructured = Unstructured::new(&buf);
19271 Self::arbitrary(&mut unstructured).unwrap_or_default()
19272 }
19273}
19274impl Default for MISSION_CURRENT_DATA {
19275 fn default() -> Self {
19276 Self::DEFAULT.clone()
19277 }
19278}
19279impl MessageData for MISSION_CURRENT_DATA {
19280 type Message = MavMessage;
19281 const ID: u32 = 42u32;
19282 const NAME: &'static str = "MISSION_CURRENT";
19283 const EXTRA_CRC: u8 = 28u8;
19284 const ENCODED_LEN: usize = 18usize;
19285 fn deser(
19286 _version: MavlinkVersion,
19287 __input: &[u8],
19288 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19289 let avail_len = __input.len();
19290 let mut payload_buf = [0; Self::ENCODED_LEN];
19291 let mut buf = if avail_len < Self::ENCODED_LEN {
19292 payload_buf[0..avail_len].copy_from_slice(__input);
19293 Bytes::new(&payload_buf)
19294 } else {
19295 Bytes::new(__input)
19296 };
19297 let mut __struct = Self::default();
19298 __struct.seq = buf.get_u16_le();
19299 __struct.total = buf.get_u16_le();
19300 let tmp = buf.get_u8();
19301 __struct.mission_state =
19302 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
19303 enum_type: "MissionState",
19304 value: tmp as u32,
19305 })?;
19306 __struct.mission_mode = buf.get_u8();
19307 __struct.mission_id = buf.get_u32_le();
19308 __struct.fence_id = buf.get_u32_le();
19309 __struct.rally_points_id = buf.get_u32_le();
19310 Ok(__struct)
19311 }
19312 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19313 let mut __tmp = BytesMut::new(bytes);
19314 #[allow(clippy::absurd_extreme_comparisons)]
19315 #[allow(unused_comparisons)]
19316 if __tmp.remaining() < Self::ENCODED_LEN {
19317 panic!(
19318 "buffer is too small (need {} bytes, but got {})",
19319 Self::ENCODED_LEN,
19320 __tmp.remaining(),
19321 )
19322 }
19323 __tmp.put_u16_le(self.seq);
19324 __tmp.put_u16_le(self.total);
19325 __tmp.put_u8(self.mission_state as u8);
19326 __tmp.put_u8(self.mission_mode);
19327 __tmp.put_u32_le(self.mission_id);
19328 __tmp.put_u32_le(self.fence_id);
19329 __tmp.put_u32_le(self.rally_points_id);
19330 if matches!(version, MavlinkVersion::V2) {
19331 let len = __tmp.len();
19332 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19333 } else {
19334 __tmp.len()
19335 }
19336 }
19337}
19338#[doc = "id: 117"]
19339#[doc = "Request a list of available logs. On some systems calling this may stop on-board logging until LOG_REQUEST_END is called. If there are no log files available this request shall be answered with one LOG_ENTRY message with id = 0 and num_logs = 0."]
19340#[derive(Debug, Clone, PartialEq)]
19341#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19342#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19343pub struct LOG_REQUEST_LIST_DATA {
19344 #[doc = "First log id (0 for first available)"]
19345 pub start: u16,
19346 #[doc = "Last log id (0xffff for last available)"]
19347 pub end: u16,
19348 #[doc = "System ID"]
19349 pub target_system: u8,
19350 #[doc = "Component ID"]
19351 pub target_component: u8,
19352}
19353impl LOG_REQUEST_LIST_DATA {
19354 pub const ENCODED_LEN: usize = 6usize;
19355 pub const DEFAULT: Self = Self {
19356 start: 0_u16,
19357 end: 0_u16,
19358 target_system: 0_u8,
19359 target_component: 0_u8,
19360 };
19361 #[cfg(feature = "arbitrary")]
19362 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19363 use arbitrary::{Arbitrary, Unstructured};
19364 let mut buf = [0u8; 1024];
19365 rng.fill_bytes(&mut buf);
19366 let mut unstructured = Unstructured::new(&buf);
19367 Self::arbitrary(&mut unstructured).unwrap_or_default()
19368 }
19369}
19370impl Default for LOG_REQUEST_LIST_DATA {
19371 fn default() -> Self {
19372 Self::DEFAULT.clone()
19373 }
19374}
19375impl MessageData for LOG_REQUEST_LIST_DATA {
19376 type Message = MavMessage;
19377 const ID: u32 = 117u32;
19378 const NAME: &'static str = "LOG_REQUEST_LIST";
19379 const EXTRA_CRC: u8 = 128u8;
19380 const ENCODED_LEN: usize = 6usize;
19381 fn deser(
19382 _version: MavlinkVersion,
19383 __input: &[u8],
19384 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19385 let avail_len = __input.len();
19386 let mut payload_buf = [0; Self::ENCODED_LEN];
19387 let mut buf = if avail_len < Self::ENCODED_LEN {
19388 payload_buf[0..avail_len].copy_from_slice(__input);
19389 Bytes::new(&payload_buf)
19390 } else {
19391 Bytes::new(__input)
19392 };
19393 let mut __struct = Self::default();
19394 __struct.start = buf.get_u16_le();
19395 __struct.end = buf.get_u16_le();
19396 __struct.target_system = buf.get_u8();
19397 __struct.target_component = buf.get_u8();
19398 Ok(__struct)
19399 }
19400 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19401 let mut __tmp = BytesMut::new(bytes);
19402 #[allow(clippy::absurd_extreme_comparisons)]
19403 #[allow(unused_comparisons)]
19404 if __tmp.remaining() < Self::ENCODED_LEN {
19405 panic!(
19406 "buffer is too small (need {} bytes, but got {})",
19407 Self::ENCODED_LEN,
19408 __tmp.remaining(),
19409 )
19410 }
19411 __tmp.put_u16_le(self.start);
19412 __tmp.put_u16_le(self.end);
19413 __tmp.put_u8(self.target_system);
19414 __tmp.put_u8(self.target_component);
19415 if matches!(version, MavlinkVersion::V2) {
19416 let len = __tmp.len();
19417 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19418 } else {
19419 __tmp.len()
19420 }
19421 }
19422}
19423#[doc = "id: 335"]
19424#[doc = "Status of the Iridium SBD link."]
19425#[derive(Debug, Clone, PartialEq)]
19426#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19427#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19428pub struct ISBD_LINK_STATUS_DATA {
19429 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
19430 pub timestamp: u64,
19431 #[doc = "Timestamp of the last successful sbd session. The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
19432 pub last_heartbeat: u64,
19433 #[doc = "Number of failed SBD sessions."]
19434 pub failed_sessions: u16,
19435 #[doc = "Number of successful SBD sessions."]
19436 pub successful_sessions: u16,
19437 #[doc = "Signal quality equal to the number of bars displayed on the ISU signal strength indicator. Range is 0 to 5, where 0 indicates no signal and 5 indicates maximum signal strength."]
19438 pub signal_quality: u8,
19439 #[doc = "1: Ring call pending, 0: No call pending."]
19440 pub ring_pending: u8,
19441 #[doc = "1: Transmission session pending, 0: No transmission session pending."]
19442 pub tx_session_pending: u8,
19443 #[doc = "1: Receiving session pending, 0: No receiving session pending."]
19444 pub rx_session_pending: u8,
19445}
19446impl ISBD_LINK_STATUS_DATA {
19447 pub const ENCODED_LEN: usize = 24usize;
19448 pub const DEFAULT: Self = Self {
19449 timestamp: 0_u64,
19450 last_heartbeat: 0_u64,
19451 failed_sessions: 0_u16,
19452 successful_sessions: 0_u16,
19453 signal_quality: 0_u8,
19454 ring_pending: 0_u8,
19455 tx_session_pending: 0_u8,
19456 rx_session_pending: 0_u8,
19457 };
19458 #[cfg(feature = "arbitrary")]
19459 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19460 use arbitrary::{Arbitrary, Unstructured};
19461 let mut buf = [0u8; 1024];
19462 rng.fill_bytes(&mut buf);
19463 let mut unstructured = Unstructured::new(&buf);
19464 Self::arbitrary(&mut unstructured).unwrap_or_default()
19465 }
19466}
19467impl Default for ISBD_LINK_STATUS_DATA {
19468 fn default() -> Self {
19469 Self::DEFAULT.clone()
19470 }
19471}
19472impl MessageData for ISBD_LINK_STATUS_DATA {
19473 type Message = MavMessage;
19474 const ID: u32 = 335u32;
19475 const NAME: &'static str = "ISBD_LINK_STATUS";
19476 const EXTRA_CRC: u8 = 225u8;
19477 const ENCODED_LEN: usize = 24usize;
19478 fn deser(
19479 _version: MavlinkVersion,
19480 __input: &[u8],
19481 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19482 let avail_len = __input.len();
19483 let mut payload_buf = [0; Self::ENCODED_LEN];
19484 let mut buf = if avail_len < Self::ENCODED_LEN {
19485 payload_buf[0..avail_len].copy_from_slice(__input);
19486 Bytes::new(&payload_buf)
19487 } else {
19488 Bytes::new(__input)
19489 };
19490 let mut __struct = Self::default();
19491 __struct.timestamp = buf.get_u64_le();
19492 __struct.last_heartbeat = buf.get_u64_le();
19493 __struct.failed_sessions = buf.get_u16_le();
19494 __struct.successful_sessions = buf.get_u16_le();
19495 __struct.signal_quality = buf.get_u8();
19496 __struct.ring_pending = buf.get_u8();
19497 __struct.tx_session_pending = buf.get_u8();
19498 __struct.rx_session_pending = buf.get_u8();
19499 Ok(__struct)
19500 }
19501 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19502 let mut __tmp = BytesMut::new(bytes);
19503 #[allow(clippy::absurd_extreme_comparisons)]
19504 #[allow(unused_comparisons)]
19505 if __tmp.remaining() < Self::ENCODED_LEN {
19506 panic!(
19507 "buffer is too small (need {} bytes, but got {})",
19508 Self::ENCODED_LEN,
19509 __tmp.remaining(),
19510 )
19511 }
19512 __tmp.put_u64_le(self.timestamp);
19513 __tmp.put_u64_le(self.last_heartbeat);
19514 __tmp.put_u16_le(self.failed_sessions);
19515 __tmp.put_u16_le(self.successful_sessions);
19516 __tmp.put_u8(self.signal_quality);
19517 __tmp.put_u8(self.ring_pending);
19518 __tmp.put_u8(self.tx_session_pending);
19519 __tmp.put_u8(self.rx_session_pending);
19520 if matches!(version, MavlinkVersion::V2) {
19521 let len = __tmp.len();
19522 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19523 } else {
19524 __tmp.len()
19525 }
19526 }
19527}
19528#[doc = "id: 324"]
19529#[doc = "Response from a PARAM_EXT_SET message."]
19530#[derive(Debug, Clone, PartialEq)]
19531#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19532#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19533pub struct PARAM_EXT_ACK_DATA {
19534 #[doc = "Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string"]
19535 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
19536 pub param_id: [u8; 16],
19537 #[doc = "Parameter value (new value if PARAM_ACK_ACCEPTED, current value otherwise)"]
19538 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
19539 pub param_value: [u8; 128],
19540 #[doc = "Parameter type."]
19541 pub param_type: MavParamExtType,
19542 #[doc = "Result code."]
19543 pub param_result: ParamAck,
19544}
19545impl PARAM_EXT_ACK_DATA {
19546 pub const ENCODED_LEN: usize = 146usize;
19547 pub const DEFAULT: Self = Self {
19548 param_id: [0_u8; 16usize],
19549 param_value: [0_u8; 128usize],
19550 param_type: MavParamExtType::DEFAULT,
19551 param_result: ParamAck::DEFAULT,
19552 };
19553 #[cfg(feature = "arbitrary")]
19554 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19555 use arbitrary::{Arbitrary, Unstructured};
19556 let mut buf = [0u8; 1024];
19557 rng.fill_bytes(&mut buf);
19558 let mut unstructured = Unstructured::new(&buf);
19559 Self::arbitrary(&mut unstructured).unwrap_or_default()
19560 }
19561}
19562impl Default for PARAM_EXT_ACK_DATA {
19563 fn default() -> Self {
19564 Self::DEFAULT.clone()
19565 }
19566}
19567impl MessageData for PARAM_EXT_ACK_DATA {
19568 type Message = MavMessage;
19569 const ID: u32 = 324u32;
19570 const NAME: &'static str = "PARAM_EXT_ACK";
19571 const EXTRA_CRC: u8 = 132u8;
19572 const ENCODED_LEN: usize = 146usize;
19573 fn deser(
19574 _version: MavlinkVersion,
19575 __input: &[u8],
19576 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19577 let avail_len = __input.len();
19578 let mut payload_buf = [0; Self::ENCODED_LEN];
19579 let mut buf = if avail_len < Self::ENCODED_LEN {
19580 payload_buf[0..avail_len].copy_from_slice(__input);
19581 Bytes::new(&payload_buf)
19582 } else {
19583 Bytes::new(__input)
19584 };
19585 let mut __struct = Self::default();
19586 for v in &mut __struct.param_id {
19587 let val = buf.get_u8();
19588 *v = val;
19589 }
19590 for v in &mut __struct.param_value {
19591 let val = buf.get_u8();
19592 *v = val;
19593 }
19594 let tmp = buf.get_u8();
19595 __struct.param_type =
19596 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
19597 enum_type: "MavParamExtType",
19598 value: tmp as u32,
19599 })?;
19600 let tmp = buf.get_u8();
19601 __struct.param_result =
19602 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
19603 enum_type: "ParamAck",
19604 value: tmp as u32,
19605 })?;
19606 Ok(__struct)
19607 }
19608 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19609 let mut __tmp = BytesMut::new(bytes);
19610 #[allow(clippy::absurd_extreme_comparisons)]
19611 #[allow(unused_comparisons)]
19612 if __tmp.remaining() < Self::ENCODED_LEN {
19613 panic!(
19614 "buffer is too small (need {} bytes, but got {})",
19615 Self::ENCODED_LEN,
19616 __tmp.remaining(),
19617 )
19618 }
19619 for val in &self.param_id {
19620 __tmp.put_u8(*val);
19621 }
19622 for val in &self.param_value {
19623 __tmp.put_u8(*val);
19624 }
19625 __tmp.put_u8(self.param_type as u8);
19626 __tmp.put_u8(self.param_result as u8);
19627 if matches!(version, MavlinkVersion::V2) {
19628 let len = __tmp.len();
19629 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19630 } else {
19631 __tmp.len()
19632 }
19633 }
19634}
19635#[doc = "id: 256"]
19636#[doc = "Setup a MAVLink2 signing key. If called with secret_key of all zero and zero initial_timestamp will disable signing."]
19637#[derive(Debug, Clone, PartialEq)]
19638#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19639#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19640pub struct SETUP_SIGNING_DATA {
19641 #[doc = "initial timestamp"]
19642 pub initial_timestamp: u64,
19643 #[doc = "system id of the target"]
19644 pub target_system: u8,
19645 #[doc = "component ID of the target"]
19646 pub target_component: u8,
19647 #[doc = "signing key"]
19648 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
19649 pub secret_key: [u8; 32],
19650}
19651impl SETUP_SIGNING_DATA {
19652 pub const ENCODED_LEN: usize = 42usize;
19653 pub const DEFAULT: Self = Self {
19654 initial_timestamp: 0_u64,
19655 target_system: 0_u8,
19656 target_component: 0_u8,
19657 secret_key: [0_u8; 32usize],
19658 };
19659 #[cfg(feature = "arbitrary")]
19660 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19661 use arbitrary::{Arbitrary, Unstructured};
19662 let mut buf = [0u8; 1024];
19663 rng.fill_bytes(&mut buf);
19664 let mut unstructured = Unstructured::new(&buf);
19665 Self::arbitrary(&mut unstructured).unwrap_or_default()
19666 }
19667}
19668impl Default for SETUP_SIGNING_DATA {
19669 fn default() -> Self {
19670 Self::DEFAULT.clone()
19671 }
19672}
19673impl MessageData for SETUP_SIGNING_DATA {
19674 type Message = MavMessage;
19675 const ID: u32 = 256u32;
19676 const NAME: &'static str = "SETUP_SIGNING";
19677 const EXTRA_CRC: u8 = 71u8;
19678 const ENCODED_LEN: usize = 42usize;
19679 fn deser(
19680 _version: MavlinkVersion,
19681 __input: &[u8],
19682 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19683 let avail_len = __input.len();
19684 let mut payload_buf = [0; Self::ENCODED_LEN];
19685 let mut buf = if avail_len < Self::ENCODED_LEN {
19686 payload_buf[0..avail_len].copy_from_slice(__input);
19687 Bytes::new(&payload_buf)
19688 } else {
19689 Bytes::new(__input)
19690 };
19691 let mut __struct = Self::default();
19692 __struct.initial_timestamp = buf.get_u64_le();
19693 __struct.target_system = buf.get_u8();
19694 __struct.target_component = buf.get_u8();
19695 for v in &mut __struct.secret_key {
19696 let val = buf.get_u8();
19697 *v = val;
19698 }
19699 Ok(__struct)
19700 }
19701 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19702 let mut __tmp = BytesMut::new(bytes);
19703 #[allow(clippy::absurd_extreme_comparisons)]
19704 #[allow(unused_comparisons)]
19705 if __tmp.remaining() < Self::ENCODED_LEN {
19706 panic!(
19707 "buffer is too small (need {} bytes, but got {})",
19708 Self::ENCODED_LEN,
19709 __tmp.remaining(),
19710 )
19711 }
19712 __tmp.put_u64_le(self.initial_timestamp);
19713 __tmp.put_u8(self.target_system);
19714 __tmp.put_u8(self.target_component);
19715 for val in &self.secret_key {
19716 __tmp.put_u8(*val);
19717 }
19718 if matches!(version, MavlinkVersion::V2) {
19719 let len = __tmp.len();
19720 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19721 } else {
19722 __tmp.len()
19723 }
19724 }
19725}
19726#[doc = "id: 435"]
19727#[doc = "Information about a flight mode. The message can be enumerated to get information for all modes, or requested for a particular mode, using MAV_CMD_REQUEST_MESSAGE. Specify 0 in param2 to request that the message is emitted for all available modes or the specific index for just one mode. The modes must be available/settable for the current vehicle/frame type. Each mode should only be emitted once (even if it is both standard and custom). Note that the current mode should be emitted in CURRENT_MODE, and that if the mode list can change then AVAILABLE_MODES_MONITOR must be emitted on first change and subsequently streamed. See <https://mavlink.io/en/services/standard_modes.html>."]
19728#[derive(Debug, Clone, PartialEq)]
19729#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19730#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19731pub struct AVAILABLE_MODES_DATA {
19732 #[doc = "A bitfield for use for autopilot-specific flags"]
19733 pub custom_mode: u32,
19734 #[doc = "Mode properties."]
19735 pub properties: MavModeProperty,
19736 #[doc = "The total number of available modes for the current vehicle type."]
19737 pub number_modes: u8,
19738 #[doc = "The current mode index within number_modes, indexed from 1. The index is not guaranteed to be persistent, and may change between reboots or if the set of modes change."]
19739 pub mode_index: u8,
19740 #[doc = "Standard mode."]
19741 pub standard_mode: MavStandardMode,
19742 #[doc = "Name of custom mode, with null termination character. Should be omitted for standard modes."]
19743 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
19744 pub mode_name: [u8; 35],
19745}
19746impl AVAILABLE_MODES_DATA {
19747 pub const ENCODED_LEN: usize = 46usize;
19748 pub const DEFAULT: Self = Self {
19749 custom_mode: 0_u32,
19750 properties: MavModeProperty::DEFAULT,
19751 number_modes: 0_u8,
19752 mode_index: 0_u8,
19753 standard_mode: MavStandardMode::DEFAULT,
19754 mode_name: [0_u8; 35usize],
19755 };
19756 #[cfg(feature = "arbitrary")]
19757 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19758 use arbitrary::{Arbitrary, Unstructured};
19759 let mut buf = [0u8; 1024];
19760 rng.fill_bytes(&mut buf);
19761 let mut unstructured = Unstructured::new(&buf);
19762 Self::arbitrary(&mut unstructured).unwrap_or_default()
19763 }
19764}
19765impl Default for AVAILABLE_MODES_DATA {
19766 fn default() -> Self {
19767 Self::DEFAULT.clone()
19768 }
19769}
19770impl MessageData for AVAILABLE_MODES_DATA {
19771 type Message = MavMessage;
19772 const ID: u32 = 435u32;
19773 const NAME: &'static str = "AVAILABLE_MODES";
19774 const EXTRA_CRC: u8 = 134u8;
19775 const ENCODED_LEN: usize = 46usize;
19776 fn deser(
19777 _version: MavlinkVersion,
19778 __input: &[u8],
19779 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19780 let avail_len = __input.len();
19781 let mut payload_buf = [0; Self::ENCODED_LEN];
19782 let mut buf = if avail_len < Self::ENCODED_LEN {
19783 payload_buf[0..avail_len].copy_from_slice(__input);
19784 Bytes::new(&payload_buf)
19785 } else {
19786 Bytes::new(__input)
19787 };
19788 let mut __struct = Self::default();
19789 __struct.custom_mode = buf.get_u32_le();
19790 let tmp = buf.get_u32_le();
19791 __struct.properties = MavModeProperty::from_bits(tmp & MavModeProperty::all().bits())
19792 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
19793 flag_type: "MavModeProperty",
19794 value: tmp as u32,
19795 })?;
19796 __struct.number_modes = buf.get_u8();
19797 __struct.mode_index = buf.get_u8();
19798 let tmp = buf.get_u8();
19799 __struct.standard_mode =
19800 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
19801 enum_type: "MavStandardMode",
19802 value: tmp as u32,
19803 })?;
19804 for v in &mut __struct.mode_name {
19805 let val = buf.get_u8();
19806 *v = val;
19807 }
19808 Ok(__struct)
19809 }
19810 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19811 let mut __tmp = BytesMut::new(bytes);
19812 #[allow(clippy::absurd_extreme_comparisons)]
19813 #[allow(unused_comparisons)]
19814 if __tmp.remaining() < Self::ENCODED_LEN {
19815 panic!(
19816 "buffer is too small (need {} bytes, but got {})",
19817 Self::ENCODED_LEN,
19818 __tmp.remaining(),
19819 )
19820 }
19821 __tmp.put_u32_le(self.custom_mode);
19822 __tmp.put_u32_le(self.properties.bits());
19823 __tmp.put_u8(self.number_modes);
19824 __tmp.put_u8(self.mode_index);
19825 __tmp.put_u8(self.standard_mode as u8);
19826 for val in &self.mode_name {
19827 __tmp.put_u8(*val);
19828 }
19829 if matches!(version, MavlinkVersion::V2) {
19830 let len = __tmp.len();
19831 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19832 } else {
19833 __tmp.len()
19834 }
19835 }
19836}
19837#[doc = "id: 54"]
19838#[doc = "Set a safety zone (volume), which is defined by two corners of a cube. This message can be used to tell the MAV which setpoints/waypoints to accept and which to reject. Safety areas are often enforced by national or competition regulations."]
19839#[derive(Debug, Clone, PartialEq)]
19840#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19841#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19842pub struct SAFETY_SET_ALLOWED_AREA_DATA {
19843 #[doc = "x position 1 / Latitude 1"]
19844 pub p1x: f32,
19845 #[doc = "y position 1 / Longitude 1"]
19846 pub p1y: f32,
19847 #[doc = "z position 1 / Altitude 1"]
19848 pub p1z: f32,
19849 #[doc = "x position 2 / Latitude 2"]
19850 pub p2x: f32,
19851 #[doc = "y position 2 / Longitude 2"]
19852 pub p2y: f32,
19853 #[doc = "z position 2 / Altitude 2"]
19854 pub p2z: f32,
19855 #[doc = "System ID"]
19856 pub target_system: u8,
19857 #[doc = "Component ID"]
19858 pub target_component: u8,
19859 #[doc = "Coordinate frame. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down."]
19860 pub frame: MavFrame,
19861}
19862impl SAFETY_SET_ALLOWED_AREA_DATA {
19863 pub const ENCODED_LEN: usize = 27usize;
19864 pub const DEFAULT: Self = Self {
19865 p1x: 0.0_f32,
19866 p1y: 0.0_f32,
19867 p1z: 0.0_f32,
19868 p2x: 0.0_f32,
19869 p2y: 0.0_f32,
19870 p2z: 0.0_f32,
19871 target_system: 0_u8,
19872 target_component: 0_u8,
19873 frame: MavFrame::DEFAULT,
19874 };
19875 #[cfg(feature = "arbitrary")]
19876 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19877 use arbitrary::{Arbitrary, Unstructured};
19878 let mut buf = [0u8; 1024];
19879 rng.fill_bytes(&mut buf);
19880 let mut unstructured = Unstructured::new(&buf);
19881 Self::arbitrary(&mut unstructured).unwrap_or_default()
19882 }
19883}
19884impl Default for SAFETY_SET_ALLOWED_AREA_DATA {
19885 fn default() -> Self {
19886 Self::DEFAULT.clone()
19887 }
19888}
19889impl MessageData for SAFETY_SET_ALLOWED_AREA_DATA {
19890 type Message = MavMessage;
19891 const ID: u32 = 54u32;
19892 const NAME: &'static str = "SAFETY_SET_ALLOWED_AREA";
19893 const EXTRA_CRC: u8 = 15u8;
19894 const ENCODED_LEN: usize = 27usize;
19895 fn deser(
19896 _version: MavlinkVersion,
19897 __input: &[u8],
19898 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19899 let avail_len = __input.len();
19900 let mut payload_buf = [0; Self::ENCODED_LEN];
19901 let mut buf = if avail_len < Self::ENCODED_LEN {
19902 payload_buf[0..avail_len].copy_from_slice(__input);
19903 Bytes::new(&payload_buf)
19904 } else {
19905 Bytes::new(__input)
19906 };
19907 let mut __struct = Self::default();
19908 __struct.p1x = buf.get_f32_le();
19909 __struct.p1y = buf.get_f32_le();
19910 __struct.p1z = buf.get_f32_le();
19911 __struct.p2x = buf.get_f32_le();
19912 __struct.p2y = buf.get_f32_le();
19913 __struct.p2z = buf.get_f32_le();
19914 __struct.target_system = buf.get_u8();
19915 __struct.target_component = buf.get_u8();
19916 let tmp = buf.get_u8();
19917 __struct.frame =
19918 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
19919 enum_type: "MavFrame",
19920 value: tmp as u32,
19921 })?;
19922 Ok(__struct)
19923 }
19924 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19925 let mut __tmp = BytesMut::new(bytes);
19926 #[allow(clippy::absurd_extreme_comparisons)]
19927 #[allow(unused_comparisons)]
19928 if __tmp.remaining() < Self::ENCODED_LEN {
19929 panic!(
19930 "buffer is too small (need {} bytes, but got {})",
19931 Self::ENCODED_LEN,
19932 __tmp.remaining(),
19933 )
19934 }
19935 __tmp.put_f32_le(self.p1x);
19936 __tmp.put_f32_le(self.p1y);
19937 __tmp.put_f32_le(self.p1z);
19938 __tmp.put_f32_le(self.p2x);
19939 __tmp.put_f32_le(self.p2y);
19940 __tmp.put_f32_le(self.p2z);
19941 __tmp.put_u8(self.target_system);
19942 __tmp.put_u8(self.target_component);
19943 __tmp.put_u8(self.frame as u8);
19944 if matches!(version, MavlinkVersion::V2) {
19945 let len = __tmp.len();
19946 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19947 } else {
19948 __tmp.len()
19949 }
19950 }
19951}
19952#[doc = "id: 82"]
19953#[doc = "Sets a desired vehicle attitude. Used by an external controller to command the vehicle (manual controller or other system)."]
19954#[derive(Debug, Clone, PartialEq)]
19955#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19956#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19957pub struct SET_ATTITUDE_TARGET_DATA {
19958 #[doc = "Timestamp (time since system boot)."]
19959 pub time_boot_ms: u32,
19960 #[doc = "Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) from MAV_FRAME_LOCAL_NED to MAV_FRAME_BODY_FRD"]
19961 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
19962 pub q: [f32; 4],
19963 #[doc = "Body roll rate"]
19964 pub body_roll_rate: f32,
19965 #[doc = "Body pitch rate"]
19966 pub body_pitch_rate: f32,
19967 #[doc = "Body yaw rate"]
19968 pub body_yaw_rate: f32,
19969 #[doc = "Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)"]
19970 pub thrust: f32,
19971 #[doc = "System ID"]
19972 pub target_system: u8,
19973 #[doc = "Component ID"]
19974 pub target_component: u8,
19975 #[doc = "Bitmap to indicate which dimensions should be ignored by the vehicle."]
19976 pub type_mask: AttitudeTargetTypemask,
19977 #[doc = "3D thrust setpoint in the body NED frame, normalized to -1 .. 1"]
19978 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
19979 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
19980 pub thrust_body: [f32; 3],
19981}
19982impl SET_ATTITUDE_TARGET_DATA {
19983 pub const ENCODED_LEN: usize = 51usize;
19984 pub const DEFAULT: Self = Self {
19985 time_boot_ms: 0_u32,
19986 q: [0.0_f32; 4usize],
19987 body_roll_rate: 0.0_f32,
19988 body_pitch_rate: 0.0_f32,
19989 body_yaw_rate: 0.0_f32,
19990 thrust: 0.0_f32,
19991 target_system: 0_u8,
19992 target_component: 0_u8,
19993 type_mask: AttitudeTargetTypemask::DEFAULT,
19994 thrust_body: [0.0_f32; 3usize],
19995 };
19996 #[cfg(feature = "arbitrary")]
19997 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19998 use arbitrary::{Arbitrary, Unstructured};
19999 let mut buf = [0u8; 1024];
20000 rng.fill_bytes(&mut buf);
20001 let mut unstructured = Unstructured::new(&buf);
20002 Self::arbitrary(&mut unstructured).unwrap_or_default()
20003 }
20004}
20005impl Default for SET_ATTITUDE_TARGET_DATA {
20006 fn default() -> Self {
20007 Self::DEFAULT.clone()
20008 }
20009}
20010impl MessageData for SET_ATTITUDE_TARGET_DATA {
20011 type Message = MavMessage;
20012 const ID: u32 = 82u32;
20013 const NAME: &'static str = "SET_ATTITUDE_TARGET";
20014 const EXTRA_CRC: u8 = 49u8;
20015 const ENCODED_LEN: usize = 51usize;
20016 fn deser(
20017 _version: MavlinkVersion,
20018 __input: &[u8],
20019 ) -> Result<Self, ::mavlink_core::error::ParserError> {
20020 let avail_len = __input.len();
20021 let mut payload_buf = [0; Self::ENCODED_LEN];
20022 let mut buf = if avail_len < Self::ENCODED_LEN {
20023 payload_buf[0..avail_len].copy_from_slice(__input);
20024 Bytes::new(&payload_buf)
20025 } else {
20026 Bytes::new(__input)
20027 };
20028 let mut __struct = Self::default();
20029 __struct.time_boot_ms = buf.get_u32_le();
20030 for v in &mut __struct.q {
20031 let val = buf.get_f32_le();
20032 *v = val;
20033 }
20034 __struct.body_roll_rate = buf.get_f32_le();
20035 __struct.body_pitch_rate = buf.get_f32_le();
20036 __struct.body_yaw_rate = buf.get_f32_le();
20037 __struct.thrust = buf.get_f32_le();
20038 __struct.target_system = buf.get_u8();
20039 __struct.target_component = buf.get_u8();
20040 let tmp = buf.get_u8();
20041 __struct.type_mask = AttitudeTargetTypemask::from_bits(
20042 tmp & AttitudeTargetTypemask::all().bits(),
20043 )
20044 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
20045 flag_type: "AttitudeTargetTypemask",
20046 value: tmp as u32,
20047 })?;
20048 for v in &mut __struct.thrust_body {
20049 let val = buf.get_f32_le();
20050 *v = val;
20051 }
20052 Ok(__struct)
20053 }
20054 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
20055 let mut __tmp = BytesMut::new(bytes);
20056 #[allow(clippy::absurd_extreme_comparisons)]
20057 #[allow(unused_comparisons)]
20058 if __tmp.remaining() < Self::ENCODED_LEN {
20059 panic!(
20060 "buffer is too small (need {} bytes, but got {})",
20061 Self::ENCODED_LEN,
20062 __tmp.remaining(),
20063 )
20064 }
20065 __tmp.put_u32_le(self.time_boot_ms);
20066 for val in &self.q {
20067 __tmp.put_f32_le(*val);
20068 }
20069 __tmp.put_f32_le(self.body_roll_rate);
20070 __tmp.put_f32_le(self.body_pitch_rate);
20071 __tmp.put_f32_le(self.body_yaw_rate);
20072 __tmp.put_f32_le(self.thrust);
20073 __tmp.put_u8(self.target_system);
20074 __tmp.put_u8(self.target_component);
20075 __tmp.put_u8(self.type_mask.bits());
20076 for val in &self.thrust_body {
20077 __tmp.put_f32_le(*val);
20078 }
20079 if matches!(version, MavlinkVersion::V2) {
20080 let len = __tmp.len();
20081 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
20082 } else {
20083 __tmp.len()
20084 }
20085 }
20086}
20087#[doc = "id: 162"]
20088#[doc = "Status of geo-fencing. Sent in extended status stream when fencing enabled."]
20089#[derive(Debug, Clone, PartialEq)]
20090#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
20091#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
20092pub struct FENCE_STATUS_DATA {
20093 #[doc = "Time (since boot) of last breach."]
20094 pub breach_time: u32,
20095 #[doc = "Number of fence breaches."]
20096 pub breach_count: u16,
20097 #[doc = "Breach status (0 if currently inside fence, 1 if outside)."]
20098 pub breach_status: u8,
20099 #[doc = "Last breach type."]
20100 pub breach_type: FenceBreach,
20101 #[doc = "Active action to prevent fence breach"]
20102 #[cfg_attr(feature = "serde", serde(default))]
20103 pub breach_mitigation: FenceMitigate,
20104}
20105impl FENCE_STATUS_DATA {
20106 pub const ENCODED_LEN: usize = 9usize;
20107 pub const DEFAULT: Self = Self {
20108 breach_time: 0_u32,
20109 breach_count: 0_u16,
20110 breach_status: 0_u8,
20111 breach_type: FenceBreach::DEFAULT,
20112 breach_mitigation: FenceMitigate::DEFAULT,
20113 };
20114 #[cfg(feature = "arbitrary")]
20115 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
20116 use arbitrary::{Arbitrary, Unstructured};
20117 let mut buf = [0u8; 1024];
20118 rng.fill_bytes(&mut buf);
20119 let mut unstructured = Unstructured::new(&buf);
20120 Self::arbitrary(&mut unstructured).unwrap_or_default()
20121 }
20122}
20123impl Default for FENCE_STATUS_DATA {
20124 fn default() -> Self {
20125 Self::DEFAULT.clone()
20126 }
20127}
20128impl MessageData for FENCE_STATUS_DATA {
20129 type Message = MavMessage;
20130 const ID: u32 = 162u32;
20131 const NAME: &'static str = "FENCE_STATUS";
20132 const EXTRA_CRC: u8 = 189u8;
20133 const ENCODED_LEN: usize = 9usize;
20134 fn deser(
20135 _version: MavlinkVersion,
20136 __input: &[u8],
20137 ) -> Result<Self, ::mavlink_core::error::ParserError> {
20138 let avail_len = __input.len();
20139 let mut payload_buf = [0; Self::ENCODED_LEN];
20140 let mut buf = if avail_len < Self::ENCODED_LEN {
20141 payload_buf[0..avail_len].copy_from_slice(__input);
20142 Bytes::new(&payload_buf)
20143 } else {
20144 Bytes::new(__input)
20145 };
20146 let mut __struct = Self::default();
20147 __struct.breach_time = buf.get_u32_le();
20148 __struct.breach_count = buf.get_u16_le();
20149 __struct.breach_status = buf.get_u8();
20150 let tmp = buf.get_u8();
20151 __struct.breach_type =
20152 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
20153 enum_type: "FenceBreach",
20154 value: tmp as u32,
20155 })?;
20156 let tmp = buf.get_u8();
20157 __struct.breach_mitigation =
20158 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
20159 enum_type: "FenceMitigate",
20160 value: tmp as u32,
20161 })?;
20162 Ok(__struct)
20163 }
20164 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
20165 let mut __tmp = BytesMut::new(bytes);
20166 #[allow(clippy::absurd_extreme_comparisons)]
20167 #[allow(unused_comparisons)]
20168 if __tmp.remaining() < Self::ENCODED_LEN {
20169 panic!(
20170 "buffer is too small (need {} bytes, but got {})",
20171 Self::ENCODED_LEN,
20172 __tmp.remaining(),
20173 )
20174 }
20175 __tmp.put_u32_le(self.breach_time);
20176 __tmp.put_u16_le(self.breach_count);
20177 __tmp.put_u8(self.breach_status);
20178 __tmp.put_u8(self.breach_type as u8);
20179 __tmp.put_u8(self.breach_mitigation as u8);
20180 if matches!(version, MavlinkVersion::V2) {
20181 let len = __tmp.len();
20182 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
20183 } else {
20184 __tmp.len()
20185 }
20186 }
20187}
20188#[doc = "id: 89"]
20189#[doc = "The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages of MAV X and the global coordinate frame in NED coordinates. Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention)."]
20190#[derive(Debug, Clone, PartialEq)]
20191#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
20192#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
20193pub struct LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA {
20194 #[doc = "Timestamp (time since system boot)."]
20195 pub time_boot_ms: u32,
20196 #[doc = "X Position"]
20197 pub x: f32,
20198 #[doc = "Y Position"]
20199 pub y: f32,
20200 #[doc = "Z Position"]
20201 pub z: f32,
20202 #[doc = "Roll"]
20203 pub roll: f32,
20204 #[doc = "Pitch"]
20205 pub pitch: f32,
20206 #[doc = "Yaw"]
20207 pub yaw: f32,
20208}
20209impl LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA {
20210 pub const ENCODED_LEN: usize = 28usize;
20211 pub const DEFAULT: Self = Self {
20212 time_boot_ms: 0_u32,
20213 x: 0.0_f32,
20214 y: 0.0_f32,
20215 z: 0.0_f32,
20216 roll: 0.0_f32,
20217 pitch: 0.0_f32,
20218 yaw: 0.0_f32,
20219 };
20220 #[cfg(feature = "arbitrary")]
20221 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
20222 use arbitrary::{Arbitrary, Unstructured};
20223 let mut buf = [0u8; 1024];
20224 rng.fill_bytes(&mut buf);
20225 let mut unstructured = Unstructured::new(&buf);
20226 Self::arbitrary(&mut unstructured).unwrap_or_default()
20227 }
20228}
20229impl Default for LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA {
20230 fn default() -> Self {
20231 Self::DEFAULT.clone()
20232 }
20233}
20234impl MessageData for LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA {
20235 type Message = MavMessage;
20236 const ID: u32 = 89u32;
20237 const NAME: &'static str = "LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET";
20238 const EXTRA_CRC: u8 = 231u8;
20239 const ENCODED_LEN: usize = 28usize;
20240 fn deser(
20241 _version: MavlinkVersion,
20242 __input: &[u8],
20243 ) -> Result<Self, ::mavlink_core::error::ParserError> {
20244 let avail_len = __input.len();
20245 let mut payload_buf = [0; Self::ENCODED_LEN];
20246 let mut buf = if avail_len < Self::ENCODED_LEN {
20247 payload_buf[0..avail_len].copy_from_slice(__input);
20248 Bytes::new(&payload_buf)
20249 } else {
20250 Bytes::new(__input)
20251 };
20252 let mut __struct = Self::default();
20253 __struct.time_boot_ms = buf.get_u32_le();
20254 __struct.x = buf.get_f32_le();
20255 __struct.y = buf.get_f32_le();
20256 __struct.z = buf.get_f32_le();
20257 __struct.roll = buf.get_f32_le();
20258 __struct.pitch = buf.get_f32_le();
20259 __struct.yaw = buf.get_f32_le();
20260 Ok(__struct)
20261 }
20262 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
20263 let mut __tmp = BytesMut::new(bytes);
20264 #[allow(clippy::absurd_extreme_comparisons)]
20265 #[allow(unused_comparisons)]
20266 if __tmp.remaining() < Self::ENCODED_LEN {
20267 panic!(
20268 "buffer is too small (need {} bytes, but got {})",
20269 Self::ENCODED_LEN,
20270 __tmp.remaining(),
20271 )
20272 }
20273 __tmp.put_u32_le(self.time_boot_ms);
20274 __tmp.put_f32_le(self.x);
20275 __tmp.put_f32_le(self.y);
20276 __tmp.put_f32_le(self.z);
20277 __tmp.put_f32_le(self.roll);
20278 __tmp.put_f32_le(self.pitch);
20279 __tmp.put_f32_le(self.yaw);
20280 if matches!(version, MavlinkVersion::V2) {
20281 let len = __tmp.len();
20282 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
20283 } else {
20284 __tmp.len()
20285 }
20286 }
20287}
20288#[doc = "id: 370"]
20289#[doc = "Smart Battery information (static/infrequent update). Use for updates from: smart battery to flight stack, flight stack to GCS. Use BATTERY_STATUS for the frequent battery updates."]
20290#[derive(Debug, Clone, PartialEq)]
20291#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
20292#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
20293pub struct SMART_BATTERY_INFO_DATA {
20294 #[doc = "Capacity when full according to manufacturer, -1: field not provided."]
20295 pub capacity_full_specification: i32,
20296 #[doc = "Capacity when full (accounting for battery degradation), -1: field not provided."]
20297 pub capacity_full: i32,
20298 #[doc = "Charge/discharge cycle count. UINT16_MAX: field not provided."]
20299 pub cycle_count: u16,
20300 #[doc = "Battery weight. 0: field not provided."]
20301 pub weight: u16,
20302 #[doc = "Minimum per-cell voltage when discharging. If not supplied set to UINT16_MAX value."]
20303 pub discharge_minimum_voltage: u16,
20304 #[doc = "Minimum per-cell voltage when charging. If not supplied set to UINT16_MAX value."]
20305 pub charging_minimum_voltage: u16,
20306 #[doc = "Minimum per-cell voltage when resting. If not supplied set to UINT16_MAX value."]
20307 pub resting_minimum_voltage: u16,
20308 #[doc = "Battery ID"]
20309 pub id: u8,
20310 #[doc = "Function of the battery"]
20311 pub battery_function: MavBatteryFunction,
20312 #[doc = "Type (chemistry) of the battery"]
20313 pub mavtype: MavBatteryType,
20314 #[doc = "Serial number in ASCII characters, 0 terminated. All 0: field not provided."]
20315 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20316 pub serial_number: [u8; 16],
20317 #[doc = "Static device name in ASCII characters, 0 terminated. All 0: field not provided. Encode as manufacturer name then product name separated using an underscore."]
20318 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20319 pub device_name: [u8; 50],
20320 #[doc = "Maximum per-cell voltage when charged. 0: field not provided."]
20321 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
20322 pub charging_maximum_voltage: u16,
20323 #[doc = "Number of battery cells in series. 0: field not provided."]
20324 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
20325 pub cells_in_series: u8,
20326 #[doc = "Maximum pack discharge current. 0: field not provided."]
20327 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
20328 pub discharge_maximum_current: u32,
20329 #[doc = "Maximum pack discharge burst current. 0: field not provided."]
20330 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
20331 pub discharge_maximum_burst_current: u32,
20332 #[doc = "Manufacture date (DD/MM/YYYY) in ASCII characters, 0 terminated. All 0: field not provided."]
20333 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
20334 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20335 pub manufacture_date: [u8; 11],
20336}
20337impl SMART_BATTERY_INFO_DATA {
20338 pub const ENCODED_LEN: usize = 109usize;
20339 pub const DEFAULT: Self = Self {
20340 capacity_full_specification: 0_i32,
20341 capacity_full: 0_i32,
20342 cycle_count: 0_u16,
20343 weight: 0_u16,
20344 discharge_minimum_voltage: 0_u16,
20345 charging_minimum_voltage: 0_u16,
20346 resting_minimum_voltage: 0_u16,
20347 id: 0_u8,
20348 battery_function: MavBatteryFunction::DEFAULT,
20349 mavtype: MavBatteryType::DEFAULT,
20350 serial_number: [0_u8; 16usize],
20351 device_name: [0_u8; 50usize],
20352 charging_maximum_voltage: 0_u16,
20353 cells_in_series: 0_u8,
20354 discharge_maximum_current: 0_u32,
20355 discharge_maximum_burst_current: 0_u32,
20356 manufacture_date: [0_u8; 11usize],
20357 };
20358 #[cfg(feature = "arbitrary")]
20359 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
20360 use arbitrary::{Arbitrary, Unstructured};
20361 let mut buf = [0u8; 1024];
20362 rng.fill_bytes(&mut buf);
20363 let mut unstructured = Unstructured::new(&buf);
20364 Self::arbitrary(&mut unstructured).unwrap_or_default()
20365 }
20366}
20367impl Default for SMART_BATTERY_INFO_DATA {
20368 fn default() -> Self {
20369 Self::DEFAULT.clone()
20370 }
20371}
20372impl MessageData for SMART_BATTERY_INFO_DATA {
20373 type Message = MavMessage;
20374 const ID: u32 = 370u32;
20375 const NAME: &'static str = "SMART_BATTERY_INFO";
20376 const EXTRA_CRC: u8 = 75u8;
20377 const ENCODED_LEN: usize = 109usize;
20378 fn deser(
20379 _version: MavlinkVersion,
20380 __input: &[u8],
20381 ) -> Result<Self, ::mavlink_core::error::ParserError> {
20382 let avail_len = __input.len();
20383 let mut payload_buf = [0; Self::ENCODED_LEN];
20384 let mut buf = if avail_len < Self::ENCODED_LEN {
20385 payload_buf[0..avail_len].copy_from_slice(__input);
20386 Bytes::new(&payload_buf)
20387 } else {
20388 Bytes::new(__input)
20389 };
20390 let mut __struct = Self::default();
20391 __struct.capacity_full_specification = buf.get_i32_le();
20392 __struct.capacity_full = buf.get_i32_le();
20393 __struct.cycle_count = buf.get_u16_le();
20394 __struct.weight = buf.get_u16_le();
20395 __struct.discharge_minimum_voltage = buf.get_u16_le();
20396 __struct.charging_minimum_voltage = buf.get_u16_le();
20397 __struct.resting_minimum_voltage = buf.get_u16_le();
20398 __struct.id = buf.get_u8();
20399 let tmp = buf.get_u8();
20400 __struct.battery_function =
20401 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
20402 enum_type: "MavBatteryFunction",
20403 value: tmp as u32,
20404 })?;
20405 let tmp = buf.get_u8();
20406 __struct.mavtype =
20407 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
20408 enum_type: "MavBatteryType",
20409 value: tmp as u32,
20410 })?;
20411 for v in &mut __struct.serial_number {
20412 let val = buf.get_u8();
20413 *v = val;
20414 }
20415 for v in &mut __struct.device_name {
20416 let val = buf.get_u8();
20417 *v = val;
20418 }
20419 __struct.charging_maximum_voltage = buf.get_u16_le();
20420 __struct.cells_in_series = buf.get_u8();
20421 __struct.discharge_maximum_current = buf.get_u32_le();
20422 __struct.discharge_maximum_burst_current = buf.get_u32_le();
20423 for v in &mut __struct.manufacture_date {
20424 let val = buf.get_u8();
20425 *v = val;
20426 }
20427 Ok(__struct)
20428 }
20429 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
20430 let mut __tmp = BytesMut::new(bytes);
20431 #[allow(clippy::absurd_extreme_comparisons)]
20432 #[allow(unused_comparisons)]
20433 if __tmp.remaining() < Self::ENCODED_LEN {
20434 panic!(
20435 "buffer is too small (need {} bytes, but got {})",
20436 Self::ENCODED_LEN,
20437 __tmp.remaining(),
20438 )
20439 }
20440 __tmp.put_i32_le(self.capacity_full_specification);
20441 __tmp.put_i32_le(self.capacity_full);
20442 __tmp.put_u16_le(self.cycle_count);
20443 __tmp.put_u16_le(self.weight);
20444 __tmp.put_u16_le(self.discharge_minimum_voltage);
20445 __tmp.put_u16_le(self.charging_minimum_voltage);
20446 __tmp.put_u16_le(self.resting_minimum_voltage);
20447 __tmp.put_u8(self.id);
20448 __tmp.put_u8(self.battery_function as u8);
20449 __tmp.put_u8(self.mavtype as u8);
20450 for val in &self.serial_number {
20451 __tmp.put_u8(*val);
20452 }
20453 for val in &self.device_name {
20454 __tmp.put_u8(*val);
20455 }
20456 __tmp.put_u16_le(self.charging_maximum_voltage);
20457 __tmp.put_u8(self.cells_in_series);
20458 __tmp.put_u32_le(self.discharge_maximum_current);
20459 __tmp.put_u32_le(self.discharge_maximum_burst_current);
20460 for val in &self.manufacture_date {
20461 __tmp.put_u8(*val);
20462 }
20463 if matches!(version, MavlinkVersion::V2) {
20464 let len = __tmp.len();
20465 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
20466 } else {
20467 __tmp.len()
20468 }
20469 }
20470}
20471#[doc = "id: 12915"]
20472#[doc = "An OpenDroneID message pack is a container for multiple encoded OpenDroneID messages (i.e. not in the format given for the above message descriptions but after encoding into the compressed OpenDroneID byte format). Used e.g. when transmitting on Bluetooth 5.0 Long Range/Extended Advertising or on WiFi Neighbor Aware Networking or on WiFi Beacon."]
20473#[derive(Debug, Clone, PartialEq)]
20474#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
20475#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
20476pub struct OPEN_DRONE_ID_MESSAGE_PACK_DATA {
20477 #[doc = "System ID (0 for broadcast)."]
20478 pub target_system: u8,
20479 #[doc = "Component ID (0 for broadcast)."]
20480 pub target_component: u8,
20481 #[doc = "Only used for drone ID data received from other UAs. See detailed description at <https://mavlink.io/en/services/opendroneid.html>."]
20482 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20483 pub id_or_mac: [u8; 20],
20484 #[doc = "This field must currently always be equal to 25 (bytes), since all encoded OpenDroneID messages are specified to have this length."]
20485 pub single_message_size: u8,
20486 #[doc = "Number of encoded messages in the pack (not the number of bytes). Allowed range is 1 - 9."]
20487 pub msg_pack_size: u8,
20488 #[doc = "Concatenation of encoded OpenDroneID messages. Shall be filled with nulls in the unused portion of the field."]
20489 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20490 pub messages: [u8; 225],
20491}
20492impl OPEN_DRONE_ID_MESSAGE_PACK_DATA {
20493 pub const ENCODED_LEN: usize = 249usize;
20494 pub const DEFAULT: Self = Self {
20495 target_system: 0_u8,
20496 target_component: 0_u8,
20497 id_or_mac: [0_u8; 20usize],
20498 single_message_size: 0_u8,
20499 msg_pack_size: 0_u8,
20500 messages: [0_u8; 225usize],
20501 };
20502 #[cfg(feature = "arbitrary")]
20503 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
20504 use arbitrary::{Arbitrary, Unstructured};
20505 let mut buf = [0u8; 1024];
20506 rng.fill_bytes(&mut buf);
20507 let mut unstructured = Unstructured::new(&buf);
20508 Self::arbitrary(&mut unstructured).unwrap_or_default()
20509 }
20510}
20511impl Default for OPEN_DRONE_ID_MESSAGE_PACK_DATA {
20512 fn default() -> Self {
20513 Self::DEFAULT.clone()
20514 }
20515}
20516impl MessageData for OPEN_DRONE_ID_MESSAGE_PACK_DATA {
20517 type Message = MavMessage;
20518 const ID: u32 = 12915u32;
20519 const NAME: &'static str = "OPEN_DRONE_ID_MESSAGE_PACK";
20520 const EXTRA_CRC: u8 = 94u8;
20521 const ENCODED_LEN: usize = 249usize;
20522 fn deser(
20523 _version: MavlinkVersion,
20524 __input: &[u8],
20525 ) -> Result<Self, ::mavlink_core::error::ParserError> {
20526 let avail_len = __input.len();
20527 let mut payload_buf = [0; Self::ENCODED_LEN];
20528 let mut buf = if avail_len < Self::ENCODED_LEN {
20529 payload_buf[0..avail_len].copy_from_slice(__input);
20530 Bytes::new(&payload_buf)
20531 } else {
20532 Bytes::new(__input)
20533 };
20534 let mut __struct = Self::default();
20535 __struct.target_system = buf.get_u8();
20536 __struct.target_component = buf.get_u8();
20537 for v in &mut __struct.id_or_mac {
20538 let val = buf.get_u8();
20539 *v = val;
20540 }
20541 __struct.single_message_size = buf.get_u8();
20542 __struct.msg_pack_size = buf.get_u8();
20543 for v in &mut __struct.messages {
20544 let val = buf.get_u8();
20545 *v = val;
20546 }
20547 Ok(__struct)
20548 }
20549 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
20550 let mut __tmp = BytesMut::new(bytes);
20551 #[allow(clippy::absurd_extreme_comparisons)]
20552 #[allow(unused_comparisons)]
20553 if __tmp.remaining() < Self::ENCODED_LEN {
20554 panic!(
20555 "buffer is too small (need {} bytes, but got {})",
20556 Self::ENCODED_LEN,
20557 __tmp.remaining(),
20558 )
20559 }
20560 __tmp.put_u8(self.target_system);
20561 __tmp.put_u8(self.target_component);
20562 for val in &self.id_or_mac {
20563 __tmp.put_u8(*val);
20564 }
20565 __tmp.put_u8(self.single_message_size);
20566 __tmp.put_u8(self.msg_pack_size);
20567 for val in &self.messages {
20568 __tmp.put_u8(*val);
20569 }
20570 if matches!(version, MavlinkVersion::V2) {
20571 let len = __tmp.len();
20572 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
20573 } else {
20574 __tmp.len()
20575 }
20576 }
20577}
20578#[doc = "id: 380"]
20579#[doc = "Time/duration estimates for various events and actions given the current vehicle state and position."]
20580#[derive(Debug, Clone, PartialEq)]
20581#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
20582#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
20583pub struct TIME_ESTIMATE_TO_TARGET_DATA {
20584 #[doc = "Estimated time to complete the vehicle's configured \"safe return\" action from its current position (e.g. RTL, Smart RTL, etc.). -1 indicates that the vehicle is landed, or that no time estimate available."]
20585 pub safe_return: i32,
20586 #[doc = "Estimated time for vehicle to complete the LAND action from its current position. -1 indicates that the vehicle is landed, or that no time estimate available."]
20587 pub land: i32,
20588 #[doc = "Estimated time for reaching/completing the currently active mission item. -1 means no time estimate available."]
20589 pub mission_next_item: i32,
20590 #[doc = "Estimated time for completing the current mission. -1 means no mission active and/or no estimate available."]
20591 pub mission_end: i32,
20592 #[doc = "Estimated time for completing the current commanded action (i.e. Go To, Takeoff, Land, etc.). -1 means no action active and/or no estimate available."]
20593 pub commanded_action: i32,
20594}
20595impl TIME_ESTIMATE_TO_TARGET_DATA {
20596 pub const ENCODED_LEN: usize = 20usize;
20597 pub const DEFAULT: Self = Self {
20598 safe_return: 0_i32,
20599 land: 0_i32,
20600 mission_next_item: 0_i32,
20601 mission_end: 0_i32,
20602 commanded_action: 0_i32,
20603 };
20604 #[cfg(feature = "arbitrary")]
20605 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
20606 use arbitrary::{Arbitrary, Unstructured};
20607 let mut buf = [0u8; 1024];
20608 rng.fill_bytes(&mut buf);
20609 let mut unstructured = Unstructured::new(&buf);
20610 Self::arbitrary(&mut unstructured).unwrap_or_default()
20611 }
20612}
20613impl Default for TIME_ESTIMATE_TO_TARGET_DATA {
20614 fn default() -> Self {
20615 Self::DEFAULT.clone()
20616 }
20617}
20618impl MessageData for TIME_ESTIMATE_TO_TARGET_DATA {
20619 type Message = MavMessage;
20620 const ID: u32 = 380u32;
20621 const NAME: &'static str = "TIME_ESTIMATE_TO_TARGET";
20622 const EXTRA_CRC: u8 = 232u8;
20623 const ENCODED_LEN: usize = 20usize;
20624 fn deser(
20625 _version: MavlinkVersion,
20626 __input: &[u8],
20627 ) -> Result<Self, ::mavlink_core::error::ParserError> {
20628 let avail_len = __input.len();
20629 let mut payload_buf = [0; Self::ENCODED_LEN];
20630 let mut buf = if avail_len < Self::ENCODED_LEN {
20631 payload_buf[0..avail_len].copy_from_slice(__input);
20632 Bytes::new(&payload_buf)
20633 } else {
20634 Bytes::new(__input)
20635 };
20636 let mut __struct = Self::default();
20637 __struct.safe_return = buf.get_i32_le();
20638 __struct.land = buf.get_i32_le();
20639 __struct.mission_next_item = buf.get_i32_le();
20640 __struct.mission_end = buf.get_i32_le();
20641 __struct.commanded_action = buf.get_i32_le();
20642 Ok(__struct)
20643 }
20644 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
20645 let mut __tmp = BytesMut::new(bytes);
20646 #[allow(clippy::absurd_extreme_comparisons)]
20647 #[allow(unused_comparisons)]
20648 if __tmp.remaining() < Self::ENCODED_LEN {
20649 panic!(
20650 "buffer is too small (need {} bytes, but got {})",
20651 Self::ENCODED_LEN,
20652 __tmp.remaining(),
20653 )
20654 }
20655 __tmp.put_i32_le(self.safe_return);
20656 __tmp.put_i32_le(self.land);
20657 __tmp.put_i32_le(self.mission_next_item);
20658 __tmp.put_i32_le(self.mission_end);
20659 __tmp.put_i32_le(self.commanded_action);
20660 if matches!(version, MavlinkVersion::V2) {
20661 let len = __tmp.len();
20662 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
20663 } else {
20664 __tmp.len()
20665 }
20666 }
20667}
20668#[doc = "id: 262"]
20669#[doc = "Information about the status of a capture. Can be requested with a MAV_CMD_REQUEST_MESSAGE command."]
20670#[derive(Debug, Clone, PartialEq)]
20671#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
20672#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
20673pub struct CAMERA_CAPTURE_STATUS_DATA {
20674 #[doc = "Timestamp (time since system boot)."]
20675 pub time_boot_ms: u32,
20676 #[doc = "Image capture interval"]
20677 pub image_interval: f32,
20678 #[doc = "Elapsed time since recording started (0: Not supported/available). A GCS should compute recording time and use non-zero values of this field to correct any discrepancy."]
20679 pub recording_time_ms: u32,
20680 #[doc = "Available storage capacity."]
20681 pub available_capacity: f32,
20682 #[doc = "Current status of image capturing (0: idle, 1: capture in progress, 2: interval set but idle, 3: interval set and capture in progress)"]
20683 pub image_status: u8,
20684 #[doc = "Current status of video capturing (0: idle, 1: capture in progress)"]
20685 pub video_status: u8,
20686 #[doc = "Total number of images captured ('forever', or until reset using MAV_CMD_STORAGE_FORMAT)."]
20687 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
20688 pub image_count: i32,
20689 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
20690 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
20691 pub camera_device_id: u8,
20692}
20693impl CAMERA_CAPTURE_STATUS_DATA {
20694 pub const ENCODED_LEN: usize = 23usize;
20695 pub const DEFAULT: Self = Self {
20696 time_boot_ms: 0_u32,
20697 image_interval: 0.0_f32,
20698 recording_time_ms: 0_u32,
20699 available_capacity: 0.0_f32,
20700 image_status: 0_u8,
20701 video_status: 0_u8,
20702 image_count: 0_i32,
20703 camera_device_id: 0_u8,
20704 };
20705 #[cfg(feature = "arbitrary")]
20706 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
20707 use arbitrary::{Arbitrary, Unstructured};
20708 let mut buf = [0u8; 1024];
20709 rng.fill_bytes(&mut buf);
20710 let mut unstructured = Unstructured::new(&buf);
20711 Self::arbitrary(&mut unstructured).unwrap_or_default()
20712 }
20713}
20714impl Default for CAMERA_CAPTURE_STATUS_DATA {
20715 fn default() -> Self {
20716 Self::DEFAULT.clone()
20717 }
20718}
20719impl MessageData for CAMERA_CAPTURE_STATUS_DATA {
20720 type Message = MavMessage;
20721 const ID: u32 = 262u32;
20722 const NAME: &'static str = "CAMERA_CAPTURE_STATUS";
20723 const EXTRA_CRC: u8 = 12u8;
20724 const ENCODED_LEN: usize = 23usize;
20725 fn deser(
20726 _version: MavlinkVersion,
20727 __input: &[u8],
20728 ) -> Result<Self, ::mavlink_core::error::ParserError> {
20729 let avail_len = __input.len();
20730 let mut payload_buf = [0; Self::ENCODED_LEN];
20731 let mut buf = if avail_len < Self::ENCODED_LEN {
20732 payload_buf[0..avail_len].copy_from_slice(__input);
20733 Bytes::new(&payload_buf)
20734 } else {
20735 Bytes::new(__input)
20736 };
20737 let mut __struct = Self::default();
20738 __struct.time_boot_ms = buf.get_u32_le();
20739 __struct.image_interval = buf.get_f32_le();
20740 __struct.recording_time_ms = buf.get_u32_le();
20741 __struct.available_capacity = buf.get_f32_le();
20742 __struct.image_status = buf.get_u8();
20743 __struct.video_status = buf.get_u8();
20744 __struct.image_count = buf.get_i32_le();
20745 __struct.camera_device_id = buf.get_u8();
20746 Ok(__struct)
20747 }
20748 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
20749 let mut __tmp = BytesMut::new(bytes);
20750 #[allow(clippy::absurd_extreme_comparisons)]
20751 #[allow(unused_comparisons)]
20752 if __tmp.remaining() < Self::ENCODED_LEN {
20753 panic!(
20754 "buffer is too small (need {} bytes, but got {})",
20755 Self::ENCODED_LEN,
20756 __tmp.remaining(),
20757 )
20758 }
20759 __tmp.put_u32_le(self.time_boot_ms);
20760 __tmp.put_f32_le(self.image_interval);
20761 __tmp.put_u32_le(self.recording_time_ms);
20762 __tmp.put_f32_le(self.available_capacity);
20763 __tmp.put_u8(self.image_status);
20764 __tmp.put_u8(self.video_status);
20765 __tmp.put_i32_le(self.image_count);
20766 __tmp.put_u8(self.camera_device_id);
20767 if matches!(version, MavlinkVersion::V2) {
20768 let len = __tmp.len();
20769 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
20770 } else {
20771 __tmp.len()
20772 }
20773 }
20774}
20775#[doc = "id: 141"]
20776#[doc = "The current system altitude."]
20777#[derive(Debug, Clone, PartialEq)]
20778#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
20779#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
20780pub struct ALTITUDE_DATA {
20781 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
20782 pub time_usec: u64,
20783 #[doc = "This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights."]
20784 pub altitude_monotonic: f32,
20785 #[doc = "This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output MSL by default and not the WGS84 altitude."]
20786 pub altitude_amsl: f32,
20787 #[doc = "This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive."]
20788 pub altitude_local: f32,
20789 #[doc = "This is the altitude above the home position. It resets on each change of the current home position."]
20790 pub altitude_relative: f32,
20791 #[doc = "This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown."]
20792 pub altitude_terrain: f32,
20793 #[doc = "This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available."]
20794 pub bottom_clearance: f32,
20795}
20796impl ALTITUDE_DATA {
20797 pub const ENCODED_LEN: usize = 32usize;
20798 pub const DEFAULT: Self = Self {
20799 time_usec: 0_u64,
20800 altitude_monotonic: 0.0_f32,
20801 altitude_amsl: 0.0_f32,
20802 altitude_local: 0.0_f32,
20803 altitude_relative: 0.0_f32,
20804 altitude_terrain: 0.0_f32,
20805 bottom_clearance: 0.0_f32,
20806 };
20807 #[cfg(feature = "arbitrary")]
20808 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
20809 use arbitrary::{Arbitrary, Unstructured};
20810 let mut buf = [0u8; 1024];
20811 rng.fill_bytes(&mut buf);
20812 let mut unstructured = Unstructured::new(&buf);
20813 Self::arbitrary(&mut unstructured).unwrap_or_default()
20814 }
20815}
20816impl Default for ALTITUDE_DATA {
20817 fn default() -> Self {
20818 Self::DEFAULT.clone()
20819 }
20820}
20821impl MessageData for ALTITUDE_DATA {
20822 type Message = MavMessage;
20823 const ID: u32 = 141u32;
20824 const NAME: &'static str = "ALTITUDE";
20825 const EXTRA_CRC: u8 = 47u8;
20826 const ENCODED_LEN: usize = 32usize;
20827 fn deser(
20828 _version: MavlinkVersion,
20829 __input: &[u8],
20830 ) -> Result<Self, ::mavlink_core::error::ParserError> {
20831 let avail_len = __input.len();
20832 let mut payload_buf = [0; Self::ENCODED_LEN];
20833 let mut buf = if avail_len < Self::ENCODED_LEN {
20834 payload_buf[0..avail_len].copy_from_slice(__input);
20835 Bytes::new(&payload_buf)
20836 } else {
20837 Bytes::new(__input)
20838 };
20839 let mut __struct = Self::default();
20840 __struct.time_usec = buf.get_u64_le();
20841 __struct.altitude_monotonic = buf.get_f32_le();
20842 __struct.altitude_amsl = buf.get_f32_le();
20843 __struct.altitude_local = buf.get_f32_le();
20844 __struct.altitude_relative = buf.get_f32_le();
20845 __struct.altitude_terrain = buf.get_f32_le();
20846 __struct.bottom_clearance = buf.get_f32_le();
20847 Ok(__struct)
20848 }
20849 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
20850 let mut __tmp = BytesMut::new(bytes);
20851 #[allow(clippy::absurd_extreme_comparisons)]
20852 #[allow(unused_comparisons)]
20853 if __tmp.remaining() < Self::ENCODED_LEN {
20854 panic!(
20855 "buffer is too small (need {} bytes, but got {})",
20856 Self::ENCODED_LEN,
20857 __tmp.remaining(),
20858 )
20859 }
20860 __tmp.put_u64_le(self.time_usec);
20861 __tmp.put_f32_le(self.altitude_monotonic);
20862 __tmp.put_f32_le(self.altitude_amsl);
20863 __tmp.put_f32_le(self.altitude_local);
20864 __tmp.put_f32_le(self.altitude_relative);
20865 __tmp.put_f32_le(self.altitude_terrain);
20866 __tmp.put_f32_le(self.bottom_clearance);
20867 if matches!(version, MavlinkVersion::V2) {
20868 let len = __tmp.len();
20869 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
20870 } else {
20871 __tmp.len()
20872 }
20873 }
20874}
20875#[doc = "id: 250"]
20876#[doc = "To debug something using a named 3D vector."]
20877#[derive(Debug, Clone, PartialEq)]
20878#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
20879#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
20880pub struct DEBUG_VECT_DATA {
20881 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
20882 pub time_usec: u64,
20883 #[doc = "x"]
20884 pub x: f32,
20885 #[doc = "y"]
20886 pub y: f32,
20887 #[doc = "z"]
20888 pub z: f32,
20889 #[doc = "Name"]
20890 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20891 pub name: [u8; 10],
20892}
20893impl DEBUG_VECT_DATA {
20894 pub const ENCODED_LEN: usize = 30usize;
20895 pub const DEFAULT: Self = Self {
20896 time_usec: 0_u64,
20897 x: 0.0_f32,
20898 y: 0.0_f32,
20899 z: 0.0_f32,
20900 name: [0_u8; 10usize],
20901 };
20902 #[cfg(feature = "arbitrary")]
20903 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
20904 use arbitrary::{Arbitrary, Unstructured};
20905 let mut buf = [0u8; 1024];
20906 rng.fill_bytes(&mut buf);
20907 let mut unstructured = Unstructured::new(&buf);
20908 Self::arbitrary(&mut unstructured).unwrap_or_default()
20909 }
20910}
20911impl Default for DEBUG_VECT_DATA {
20912 fn default() -> Self {
20913 Self::DEFAULT.clone()
20914 }
20915}
20916impl MessageData for DEBUG_VECT_DATA {
20917 type Message = MavMessage;
20918 const ID: u32 = 250u32;
20919 const NAME: &'static str = "DEBUG_VECT";
20920 const EXTRA_CRC: u8 = 49u8;
20921 const ENCODED_LEN: usize = 30usize;
20922 fn deser(
20923 _version: MavlinkVersion,
20924 __input: &[u8],
20925 ) -> Result<Self, ::mavlink_core::error::ParserError> {
20926 let avail_len = __input.len();
20927 let mut payload_buf = [0; Self::ENCODED_LEN];
20928 let mut buf = if avail_len < Self::ENCODED_LEN {
20929 payload_buf[0..avail_len].copy_from_slice(__input);
20930 Bytes::new(&payload_buf)
20931 } else {
20932 Bytes::new(__input)
20933 };
20934 let mut __struct = Self::default();
20935 __struct.time_usec = buf.get_u64_le();
20936 __struct.x = buf.get_f32_le();
20937 __struct.y = buf.get_f32_le();
20938 __struct.z = buf.get_f32_le();
20939 for v in &mut __struct.name {
20940 let val = buf.get_u8();
20941 *v = val;
20942 }
20943 Ok(__struct)
20944 }
20945 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
20946 let mut __tmp = BytesMut::new(bytes);
20947 #[allow(clippy::absurd_extreme_comparisons)]
20948 #[allow(unused_comparisons)]
20949 if __tmp.remaining() < Self::ENCODED_LEN {
20950 panic!(
20951 "buffer is too small (need {} bytes, but got {})",
20952 Self::ENCODED_LEN,
20953 __tmp.remaining(),
20954 )
20955 }
20956 __tmp.put_u64_le(self.time_usec);
20957 __tmp.put_f32_le(self.x);
20958 __tmp.put_f32_le(self.y);
20959 __tmp.put_f32_le(self.z);
20960 for val in &self.name {
20961 __tmp.put_u8(*val);
20962 }
20963 if matches!(version, MavlinkVersion::V2) {
20964 let len = __tmp.len();
20965 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
20966 } else {
20967 __tmp.len()
20968 }
20969 }
20970}
20971#[doc = "id: 287"]
20972#[doc = "Set gimbal manager pitch and yaw angles (high rate message). This message is to be sent to the gimbal manager (e.g. from a ground station) and will be ignored by gimbal devices. Angles and rates can be set to NaN according to use case. Use MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW for low-rate adjustments that require confirmation."]
20973#[derive(Debug, Clone, PartialEq)]
20974#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
20975#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
20976pub struct GIMBAL_MANAGER_SET_PITCHYAW_DATA {
20977 #[doc = "High level gimbal manager flags to use."]
20978 pub flags: GimbalManagerFlags,
20979 #[doc = "Pitch angle (positive: up, negative: down, NaN to be ignored)."]
20980 pub pitch: f32,
20981 #[doc = "Yaw angle (positive: to the right, negative: to the left, NaN to be ignored)."]
20982 pub yaw: f32,
20983 #[doc = "Pitch angular rate (positive: up, negative: down, NaN to be ignored)."]
20984 pub pitch_rate: f32,
20985 #[doc = "Yaw angular rate (positive: to the right, negative: to the left, NaN to be ignored)."]
20986 pub yaw_rate: f32,
20987 #[doc = "System ID"]
20988 pub target_system: u8,
20989 #[doc = "Component ID"]
20990 pub target_component: u8,
20991 #[doc = "Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals)."]
20992 pub gimbal_device_id: u8,
20993}
20994impl GIMBAL_MANAGER_SET_PITCHYAW_DATA {
20995 pub const ENCODED_LEN: usize = 23usize;
20996 pub const DEFAULT: Self = Self {
20997 flags: GimbalManagerFlags::DEFAULT,
20998 pitch: 0.0_f32,
20999 yaw: 0.0_f32,
21000 pitch_rate: 0.0_f32,
21001 yaw_rate: 0.0_f32,
21002 target_system: 0_u8,
21003 target_component: 0_u8,
21004 gimbal_device_id: 0_u8,
21005 };
21006 #[cfg(feature = "arbitrary")]
21007 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
21008 use arbitrary::{Arbitrary, Unstructured};
21009 let mut buf = [0u8; 1024];
21010 rng.fill_bytes(&mut buf);
21011 let mut unstructured = Unstructured::new(&buf);
21012 Self::arbitrary(&mut unstructured).unwrap_or_default()
21013 }
21014}
21015impl Default for GIMBAL_MANAGER_SET_PITCHYAW_DATA {
21016 fn default() -> Self {
21017 Self::DEFAULT.clone()
21018 }
21019}
21020impl MessageData for GIMBAL_MANAGER_SET_PITCHYAW_DATA {
21021 type Message = MavMessage;
21022 const ID: u32 = 287u32;
21023 const NAME: &'static str = "GIMBAL_MANAGER_SET_PITCHYAW";
21024 const EXTRA_CRC: u8 = 1u8;
21025 const ENCODED_LEN: usize = 23usize;
21026 fn deser(
21027 _version: MavlinkVersion,
21028 __input: &[u8],
21029 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21030 let avail_len = __input.len();
21031 let mut payload_buf = [0; Self::ENCODED_LEN];
21032 let mut buf = if avail_len < Self::ENCODED_LEN {
21033 payload_buf[0..avail_len].copy_from_slice(__input);
21034 Bytes::new(&payload_buf)
21035 } else {
21036 Bytes::new(__input)
21037 };
21038 let mut __struct = Self::default();
21039 let tmp = buf.get_u32_le();
21040 __struct.flags = GimbalManagerFlags::from_bits(tmp & GimbalManagerFlags::all().bits())
21041 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
21042 flag_type: "GimbalManagerFlags",
21043 value: tmp as u32,
21044 })?;
21045 __struct.pitch = buf.get_f32_le();
21046 __struct.yaw = buf.get_f32_le();
21047 __struct.pitch_rate = buf.get_f32_le();
21048 __struct.yaw_rate = buf.get_f32_le();
21049 __struct.target_system = buf.get_u8();
21050 __struct.target_component = buf.get_u8();
21051 __struct.gimbal_device_id = buf.get_u8();
21052 Ok(__struct)
21053 }
21054 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21055 let mut __tmp = BytesMut::new(bytes);
21056 #[allow(clippy::absurd_extreme_comparisons)]
21057 #[allow(unused_comparisons)]
21058 if __tmp.remaining() < Self::ENCODED_LEN {
21059 panic!(
21060 "buffer is too small (need {} bytes, but got {})",
21061 Self::ENCODED_LEN,
21062 __tmp.remaining(),
21063 )
21064 }
21065 __tmp.put_u32_le(self.flags.bits());
21066 __tmp.put_f32_le(self.pitch);
21067 __tmp.put_f32_le(self.yaw);
21068 __tmp.put_f32_le(self.pitch_rate);
21069 __tmp.put_f32_le(self.yaw_rate);
21070 __tmp.put_u8(self.target_system);
21071 __tmp.put_u8(self.target_component);
21072 __tmp.put_u8(self.gimbal_device_id);
21073 if matches!(version, MavlinkVersion::V2) {
21074 let len = __tmp.len();
21075 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21076 } else {
21077 __tmp.len()
21078 }
21079 }
21080}
21081#[doc = "id: 263"]
21082#[doc = "Information about a captured image. This is emitted every time a message is captured. MAV_CMD_REQUEST_MESSAGE can be used to (re)request this message for a specific sequence number or range of sequence numbers: MAV_CMD_REQUEST_MESSAGE.param2 indicates the sequence number the first image to send, or set to -1 to send the message for all sequence numbers. MAV_CMD_REQUEST_MESSAGE.param3 is used to specify a range of messages to send: set to 0 (default) to send just the the message for the sequence number in param 2, set to -1 to send the message for the sequence number in param 2 and all the following sequence numbers, set to the sequence number of the final message in the range."]
21083#[derive(Debug, Clone, PartialEq)]
21084#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21085#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21086pub struct CAMERA_IMAGE_CAPTURED_DATA {
21087 #[doc = "Timestamp (time since UNIX epoch) in UTC. 0 for unknown."]
21088 pub time_utc: u64,
21089 #[doc = "Timestamp (time since system boot)."]
21090 pub time_boot_ms: u32,
21091 #[doc = "Latitude where image was taken"]
21092 pub lat: i32,
21093 #[doc = "Longitude where capture was taken"]
21094 pub lon: i32,
21095 #[doc = "Altitude (MSL) where image was taken"]
21096 pub alt: i32,
21097 #[doc = "Altitude above ground"]
21098 pub relative_alt: i32,
21099 #[doc = "Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)"]
21100 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
21101 pub q: [f32; 4],
21102 #[doc = "Zero based index of this image (i.e. a new image will have index CAMERA_CAPTURE_STATUS.image count -1)"]
21103 pub image_index: i32,
21104 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id). Field name is usually camera_device_id."]
21105 pub camera_id: u8,
21106 #[doc = "Boolean indicating success (1) or failure (0) while capturing this image."]
21107 pub capture_result: i8,
21108 #[doc = "URL of image taken. Either local storage or <http://foo.jpg> if camera provides an HTTP interface."]
21109 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
21110 pub file_url: [u8; 205],
21111}
21112impl CAMERA_IMAGE_CAPTURED_DATA {
21113 pub const ENCODED_LEN: usize = 255usize;
21114 pub const DEFAULT: Self = Self {
21115 time_utc: 0_u64,
21116 time_boot_ms: 0_u32,
21117 lat: 0_i32,
21118 lon: 0_i32,
21119 alt: 0_i32,
21120 relative_alt: 0_i32,
21121 q: [0.0_f32; 4usize],
21122 image_index: 0_i32,
21123 camera_id: 0_u8,
21124 capture_result: 0_i8,
21125 file_url: [0_u8; 205usize],
21126 };
21127 #[cfg(feature = "arbitrary")]
21128 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
21129 use arbitrary::{Arbitrary, Unstructured};
21130 let mut buf = [0u8; 1024];
21131 rng.fill_bytes(&mut buf);
21132 let mut unstructured = Unstructured::new(&buf);
21133 Self::arbitrary(&mut unstructured).unwrap_or_default()
21134 }
21135}
21136impl Default for CAMERA_IMAGE_CAPTURED_DATA {
21137 fn default() -> Self {
21138 Self::DEFAULT.clone()
21139 }
21140}
21141impl MessageData for CAMERA_IMAGE_CAPTURED_DATA {
21142 type Message = MavMessage;
21143 const ID: u32 = 263u32;
21144 const NAME: &'static str = "CAMERA_IMAGE_CAPTURED";
21145 const EXTRA_CRC: u8 = 133u8;
21146 const ENCODED_LEN: usize = 255usize;
21147 fn deser(
21148 _version: MavlinkVersion,
21149 __input: &[u8],
21150 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21151 let avail_len = __input.len();
21152 let mut payload_buf = [0; Self::ENCODED_LEN];
21153 let mut buf = if avail_len < Self::ENCODED_LEN {
21154 payload_buf[0..avail_len].copy_from_slice(__input);
21155 Bytes::new(&payload_buf)
21156 } else {
21157 Bytes::new(__input)
21158 };
21159 let mut __struct = Self::default();
21160 __struct.time_utc = buf.get_u64_le();
21161 __struct.time_boot_ms = buf.get_u32_le();
21162 __struct.lat = buf.get_i32_le();
21163 __struct.lon = buf.get_i32_le();
21164 __struct.alt = buf.get_i32_le();
21165 __struct.relative_alt = buf.get_i32_le();
21166 for v in &mut __struct.q {
21167 let val = buf.get_f32_le();
21168 *v = val;
21169 }
21170 __struct.image_index = buf.get_i32_le();
21171 __struct.camera_id = buf.get_u8();
21172 __struct.capture_result = buf.get_i8();
21173 for v in &mut __struct.file_url {
21174 let val = buf.get_u8();
21175 *v = val;
21176 }
21177 Ok(__struct)
21178 }
21179 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21180 let mut __tmp = BytesMut::new(bytes);
21181 #[allow(clippy::absurd_extreme_comparisons)]
21182 #[allow(unused_comparisons)]
21183 if __tmp.remaining() < Self::ENCODED_LEN {
21184 panic!(
21185 "buffer is too small (need {} bytes, but got {})",
21186 Self::ENCODED_LEN,
21187 __tmp.remaining(),
21188 )
21189 }
21190 __tmp.put_u64_le(self.time_utc);
21191 __tmp.put_u32_le(self.time_boot_ms);
21192 __tmp.put_i32_le(self.lat);
21193 __tmp.put_i32_le(self.lon);
21194 __tmp.put_i32_le(self.alt);
21195 __tmp.put_i32_le(self.relative_alt);
21196 for val in &self.q {
21197 __tmp.put_f32_le(*val);
21198 }
21199 __tmp.put_i32_le(self.image_index);
21200 __tmp.put_u8(self.camera_id);
21201 __tmp.put_i8(self.capture_result);
21202 for val in &self.file_url {
21203 __tmp.put_u8(*val);
21204 }
21205 if matches!(version, MavlinkVersion::V2) {
21206 let len = __tmp.len();
21207 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21208 } else {
21209 __tmp.len()
21210 }
21211 }
21212}
21213#[doc = "id: 76"]
21214#[doc = "Send a command with up to seven parameters to the MAV. COMMAND_INT is generally preferred when sending MAV_CMD commands that include positional information; it offers higher precision and allows the MAV_FRAME to be specified (which may otherwise be ambiguous, particularly for altitude). The command microservice is documented at <https://mavlink.io/en/services/command.html>."]
21215#[derive(Debug, Clone, PartialEq)]
21216#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21217#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21218pub struct COMMAND_LONG_DATA {
21219 #[doc = "Parameter 1 (for the specific command)."]
21220 pub param1: f32,
21221 #[doc = "Parameter 2 (for the specific command)."]
21222 pub param2: f32,
21223 #[doc = "Parameter 3 (for the specific command)."]
21224 pub param3: f32,
21225 #[doc = "Parameter 4 (for the specific command)."]
21226 pub param4: f32,
21227 #[doc = "Parameter 5 (for the specific command)."]
21228 pub param5: f32,
21229 #[doc = "Parameter 6 (for the specific command)."]
21230 pub param6: f32,
21231 #[doc = "Parameter 7 (for the specific command)."]
21232 pub param7: f32,
21233 #[doc = "Command ID (of command to send)."]
21234 pub command: MavCmd,
21235 #[doc = "System which should execute the command"]
21236 pub target_system: u8,
21237 #[doc = "Component which should execute the command, 0 for all components"]
21238 pub target_component: u8,
21239 #[doc = "0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)"]
21240 pub confirmation: u8,
21241}
21242impl COMMAND_LONG_DATA {
21243 pub const ENCODED_LEN: usize = 33usize;
21244 pub const DEFAULT: Self = Self {
21245 param1: 0.0_f32,
21246 param2: 0.0_f32,
21247 param3: 0.0_f32,
21248 param4: 0.0_f32,
21249 param5: 0.0_f32,
21250 param6: 0.0_f32,
21251 param7: 0.0_f32,
21252 command: MavCmd::DEFAULT,
21253 target_system: 0_u8,
21254 target_component: 0_u8,
21255 confirmation: 0_u8,
21256 };
21257 #[cfg(feature = "arbitrary")]
21258 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
21259 use arbitrary::{Arbitrary, Unstructured};
21260 let mut buf = [0u8; 1024];
21261 rng.fill_bytes(&mut buf);
21262 let mut unstructured = Unstructured::new(&buf);
21263 Self::arbitrary(&mut unstructured).unwrap_or_default()
21264 }
21265}
21266impl Default for COMMAND_LONG_DATA {
21267 fn default() -> Self {
21268 Self::DEFAULT.clone()
21269 }
21270}
21271impl MessageData for COMMAND_LONG_DATA {
21272 type Message = MavMessage;
21273 const ID: u32 = 76u32;
21274 const NAME: &'static str = "COMMAND_LONG";
21275 const EXTRA_CRC: u8 = 152u8;
21276 const ENCODED_LEN: usize = 33usize;
21277 fn deser(
21278 _version: MavlinkVersion,
21279 __input: &[u8],
21280 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21281 let avail_len = __input.len();
21282 let mut payload_buf = [0; Self::ENCODED_LEN];
21283 let mut buf = if avail_len < Self::ENCODED_LEN {
21284 payload_buf[0..avail_len].copy_from_slice(__input);
21285 Bytes::new(&payload_buf)
21286 } else {
21287 Bytes::new(__input)
21288 };
21289 let mut __struct = Self::default();
21290 __struct.param1 = buf.get_f32_le();
21291 __struct.param2 = buf.get_f32_le();
21292 __struct.param3 = buf.get_f32_le();
21293 __struct.param4 = buf.get_f32_le();
21294 __struct.param5 = buf.get_f32_le();
21295 __struct.param6 = buf.get_f32_le();
21296 __struct.param7 = buf.get_f32_le();
21297 let tmp = buf.get_u16_le();
21298 __struct.command = FromPrimitive::from_u16(tmp).ok_or(
21299 ::mavlink_core::error::ParserError::InvalidEnum {
21300 enum_type: "MavCmd",
21301 value: tmp as u32,
21302 },
21303 )?;
21304 __struct.target_system = buf.get_u8();
21305 __struct.target_component = buf.get_u8();
21306 __struct.confirmation = buf.get_u8();
21307 Ok(__struct)
21308 }
21309 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21310 let mut __tmp = BytesMut::new(bytes);
21311 #[allow(clippy::absurd_extreme_comparisons)]
21312 #[allow(unused_comparisons)]
21313 if __tmp.remaining() < Self::ENCODED_LEN {
21314 panic!(
21315 "buffer is too small (need {} bytes, but got {})",
21316 Self::ENCODED_LEN,
21317 __tmp.remaining(),
21318 )
21319 }
21320 __tmp.put_f32_le(self.param1);
21321 __tmp.put_f32_le(self.param2);
21322 __tmp.put_f32_le(self.param3);
21323 __tmp.put_f32_le(self.param4);
21324 __tmp.put_f32_le(self.param5);
21325 __tmp.put_f32_le(self.param6);
21326 __tmp.put_f32_le(self.param7);
21327 __tmp.put_u16_le(self.command as u16);
21328 __tmp.put_u8(self.target_system);
21329 __tmp.put_u8(self.target_component);
21330 __tmp.put_u8(self.confirmation);
21331 if matches!(version, MavlinkVersion::V2) {
21332 let len = __tmp.len();
21333 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21334 } else {
21335 __tmp.len()
21336 }
21337 }
21338}
21339#[doc = "id: 321"]
21340#[doc = "Request all parameters of this component. All parameters should be emitted in response as PARAM_EXT_VALUE."]
21341#[derive(Debug, Clone, PartialEq)]
21342#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21343#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21344pub struct PARAM_EXT_REQUEST_LIST_DATA {
21345 #[doc = "System ID"]
21346 pub target_system: u8,
21347 #[doc = "Component ID"]
21348 pub target_component: u8,
21349}
21350impl PARAM_EXT_REQUEST_LIST_DATA {
21351 pub const ENCODED_LEN: usize = 2usize;
21352 pub const DEFAULT: Self = Self {
21353 target_system: 0_u8,
21354 target_component: 0_u8,
21355 };
21356 #[cfg(feature = "arbitrary")]
21357 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
21358 use arbitrary::{Arbitrary, Unstructured};
21359 let mut buf = [0u8; 1024];
21360 rng.fill_bytes(&mut buf);
21361 let mut unstructured = Unstructured::new(&buf);
21362 Self::arbitrary(&mut unstructured).unwrap_or_default()
21363 }
21364}
21365impl Default for PARAM_EXT_REQUEST_LIST_DATA {
21366 fn default() -> Self {
21367 Self::DEFAULT.clone()
21368 }
21369}
21370impl MessageData for PARAM_EXT_REQUEST_LIST_DATA {
21371 type Message = MavMessage;
21372 const ID: u32 = 321u32;
21373 const NAME: &'static str = "PARAM_EXT_REQUEST_LIST";
21374 const EXTRA_CRC: u8 = 88u8;
21375 const ENCODED_LEN: usize = 2usize;
21376 fn deser(
21377 _version: MavlinkVersion,
21378 __input: &[u8],
21379 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21380 let avail_len = __input.len();
21381 let mut payload_buf = [0; Self::ENCODED_LEN];
21382 let mut buf = if avail_len < Self::ENCODED_LEN {
21383 payload_buf[0..avail_len].copy_from_slice(__input);
21384 Bytes::new(&payload_buf)
21385 } else {
21386 Bytes::new(__input)
21387 };
21388 let mut __struct = Self::default();
21389 __struct.target_system = buf.get_u8();
21390 __struct.target_component = buf.get_u8();
21391 Ok(__struct)
21392 }
21393 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21394 let mut __tmp = BytesMut::new(bytes);
21395 #[allow(clippy::absurd_extreme_comparisons)]
21396 #[allow(unused_comparisons)]
21397 if __tmp.remaining() < Self::ENCODED_LEN {
21398 panic!(
21399 "buffer is too small (need {} bytes, but got {})",
21400 Self::ENCODED_LEN,
21401 __tmp.remaining(),
21402 )
21403 }
21404 __tmp.put_u8(self.target_system);
21405 __tmp.put_u8(self.target_component);
21406 if matches!(version, MavlinkVersion::V2) {
21407 let len = __tmp.len();
21408 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21409 } else {
21410 __tmp.len()
21411 }
21412 }
21413}
21414#[doc = "id: 322"]
21415#[doc = "Emit the value of a parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows them to re-request missing parameters after a loss or timeout."]
21416#[derive(Debug, Clone, PartialEq)]
21417#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21418#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21419pub struct PARAM_EXT_VALUE_DATA {
21420 #[doc = "Total number of parameters"]
21421 pub param_count: u16,
21422 #[doc = "Index of this parameter"]
21423 pub param_index: u16,
21424 #[doc = "Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string"]
21425 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
21426 pub param_id: [u8; 16],
21427 #[doc = "Parameter value"]
21428 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
21429 pub param_value: [u8; 128],
21430 #[doc = "Parameter type."]
21431 pub param_type: MavParamExtType,
21432}
21433impl PARAM_EXT_VALUE_DATA {
21434 pub const ENCODED_LEN: usize = 149usize;
21435 pub const DEFAULT: Self = Self {
21436 param_count: 0_u16,
21437 param_index: 0_u16,
21438 param_id: [0_u8; 16usize],
21439 param_value: [0_u8; 128usize],
21440 param_type: MavParamExtType::DEFAULT,
21441 };
21442 #[cfg(feature = "arbitrary")]
21443 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
21444 use arbitrary::{Arbitrary, Unstructured};
21445 let mut buf = [0u8; 1024];
21446 rng.fill_bytes(&mut buf);
21447 let mut unstructured = Unstructured::new(&buf);
21448 Self::arbitrary(&mut unstructured).unwrap_or_default()
21449 }
21450}
21451impl Default for PARAM_EXT_VALUE_DATA {
21452 fn default() -> Self {
21453 Self::DEFAULT.clone()
21454 }
21455}
21456impl MessageData for PARAM_EXT_VALUE_DATA {
21457 type Message = MavMessage;
21458 const ID: u32 = 322u32;
21459 const NAME: &'static str = "PARAM_EXT_VALUE";
21460 const EXTRA_CRC: u8 = 243u8;
21461 const ENCODED_LEN: usize = 149usize;
21462 fn deser(
21463 _version: MavlinkVersion,
21464 __input: &[u8],
21465 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21466 let avail_len = __input.len();
21467 let mut payload_buf = [0; Self::ENCODED_LEN];
21468 let mut buf = if avail_len < Self::ENCODED_LEN {
21469 payload_buf[0..avail_len].copy_from_slice(__input);
21470 Bytes::new(&payload_buf)
21471 } else {
21472 Bytes::new(__input)
21473 };
21474 let mut __struct = Self::default();
21475 __struct.param_count = buf.get_u16_le();
21476 __struct.param_index = buf.get_u16_le();
21477 for v in &mut __struct.param_id {
21478 let val = buf.get_u8();
21479 *v = val;
21480 }
21481 for v in &mut __struct.param_value {
21482 let val = buf.get_u8();
21483 *v = val;
21484 }
21485 let tmp = buf.get_u8();
21486 __struct.param_type =
21487 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
21488 enum_type: "MavParamExtType",
21489 value: tmp as u32,
21490 })?;
21491 Ok(__struct)
21492 }
21493 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21494 let mut __tmp = BytesMut::new(bytes);
21495 #[allow(clippy::absurd_extreme_comparisons)]
21496 #[allow(unused_comparisons)]
21497 if __tmp.remaining() < Self::ENCODED_LEN {
21498 panic!(
21499 "buffer is too small (need {} bytes, but got {})",
21500 Self::ENCODED_LEN,
21501 __tmp.remaining(),
21502 )
21503 }
21504 __tmp.put_u16_le(self.param_count);
21505 __tmp.put_u16_le(self.param_index);
21506 for val in &self.param_id {
21507 __tmp.put_u8(*val);
21508 }
21509 for val in &self.param_value {
21510 __tmp.put_u8(*val);
21511 }
21512 __tmp.put_u8(self.param_type as u8);
21513 if matches!(version, MavlinkVersion::V2) {
21514 let len = __tmp.len();
21515 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21516 } else {
21517 __tmp.len()
21518 }
21519 }
21520}
21521#[doc = "id: 280"]
21522#[doc = "Information about a high level gimbal manager. This message should be requested by a ground station using MAV_CMD_REQUEST_MESSAGE."]
21523#[derive(Debug, Clone, PartialEq)]
21524#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21525#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21526pub struct GIMBAL_MANAGER_INFORMATION_DATA {
21527 #[doc = "Timestamp (time since system boot)."]
21528 pub time_boot_ms: u32,
21529 #[doc = "Bitmap of gimbal capability flags."]
21530 pub cap_flags: GimbalManagerCapFlags,
21531 #[doc = "Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left)"]
21532 pub roll_min: f32,
21533 #[doc = "Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left)"]
21534 pub roll_max: f32,
21535 #[doc = "Minimum pitch angle (positive: up, negative: down)"]
21536 pub pitch_min: f32,
21537 #[doc = "Maximum pitch angle (positive: up, negative: down)"]
21538 pub pitch_max: f32,
21539 #[doc = "Minimum yaw angle (positive: to the right, negative: to the left)"]
21540 pub yaw_min: f32,
21541 #[doc = "Maximum yaw angle (positive: to the right, negative: to the left)"]
21542 pub yaw_max: f32,
21543 #[doc = "Gimbal device ID that this gimbal manager is responsible for. Component ID of gimbal device (or 1-6 for non-MAVLink gimbal)."]
21544 pub gimbal_device_id: u8,
21545}
21546impl GIMBAL_MANAGER_INFORMATION_DATA {
21547 pub const ENCODED_LEN: usize = 33usize;
21548 pub const DEFAULT: Self = Self {
21549 time_boot_ms: 0_u32,
21550 cap_flags: GimbalManagerCapFlags::DEFAULT,
21551 roll_min: 0.0_f32,
21552 roll_max: 0.0_f32,
21553 pitch_min: 0.0_f32,
21554 pitch_max: 0.0_f32,
21555 yaw_min: 0.0_f32,
21556 yaw_max: 0.0_f32,
21557 gimbal_device_id: 0_u8,
21558 };
21559 #[cfg(feature = "arbitrary")]
21560 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
21561 use arbitrary::{Arbitrary, Unstructured};
21562 let mut buf = [0u8; 1024];
21563 rng.fill_bytes(&mut buf);
21564 let mut unstructured = Unstructured::new(&buf);
21565 Self::arbitrary(&mut unstructured).unwrap_or_default()
21566 }
21567}
21568impl Default for GIMBAL_MANAGER_INFORMATION_DATA {
21569 fn default() -> Self {
21570 Self::DEFAULT.clone()
21571 }
21572}
21573impl MessageData for GIMBAL_MANAGER_INFORMATION_DATA {
21574 type Message = MavMessage;
21575 const ID: u32 = 280u32;
21576 const NAME: &'static str = "GIMBAL_MANAGER_INFORMATION";
21577 const EXTRA_CRC: u8 = 70u8;
21578 const ENCODED_LEN: usize = 33usize;
21579 fn deser(
21580 _version: MavlinkVersion,
21581 __input: &[u8],
21582 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21583 let avail_len = __input.len();
21584 let mut payload_buf = [0; Self::ENCODED_LEN];
21585 let mut buf = if avail_len < Self::ENCODED_LEN {
21586 payload_buf[0..avail_len].copy_from_slice(__input);
21587 Bytes::new(&payload_buf)
21588 } else {
21589 Bytes::new(__input)
21590 };
21591 let mut __struct = Self::default();
21592 __struct.time_boot_ms = buf.get_u32_le();
21593 let tmp = buf.get_u32_le();
21594 __struct.cap_flags = GimbalManagerCapFlags::from_bits(
21595 tmp & GimbalManagerCapFlags::all().bits(),
21596 )
21597 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
21598 flag_type: "GimbalManagerCapFlags",
21599 value: tmp as u32,
21600 })?;
21601 __struct.roll_min = buf.get_f32_le();
21602 __struct.roll_max = buf.get_f32_le();
21603 __struct.pitch_min = buf.get_f32_le();
21604 __struct.pitch_max = buf.get_f32_le();
21605 __struct.yaw_min = buf.get_f32_le();
21606 __struct.yaw_max = buf.get_f32_le();
21607 __struct.gimbal_device_id = buf.get_u8();
21608 Ok(__struct)
21609 }
21610 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21611 let mut __tmp = BytesMut::new(bytes);
21612 #[allow(clippy::absurd_extreme_comparisons)]
21613 #[allow(unused_comparisons)]
21614 if __tmp.remaining() < Self::ENCODED_LEN {
21615 panic!(
21616 "buffer is too small (need {} bytes, but got {})",
21617 Self::ENCODED_LEN,
21618 __tmp.remaining(),
21619 )
21620 }
21621 __tmp.put_u32_le(self.time_boot_ms);
21622 __tmp.put_u32_le(self.cap_flags.bits());
21623 __tmp.put_f32_le(self.roll_min);
21624 __tmp.put_f32_le(self.roll_max);
21625 __tmp.put_f32_le(self.pitch_min);
21626 __tmp.put_f32_le(self.pitch_max);
21627 __tmp.put_f32_le(self.yaw_min);
21628 __tmp.put_f32_le(self.yaw_max);
21629 __tmp.put_u8(self.gimbal_device_id);
21630 if matches!(version, MavlinkVersion::V2) {
21631 let len = __tmp.len();
21632 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21633 } else {
21634 __tmp.len()
21635 }
21636 }
21637}
21638#[doc = "id: 12900"]
21639#[doc = "Data for filling the OpenDroneID Basic ID message. This and the below messages are primarily meant for feeding data to/from an OpenDroneID implementation. E.g. <https://github.com/opendroneid/opendroneid-core-c>. These messages are compatible with the ASTM F3411 Remote ID standard and the ASD-STAN prEN 4709-002 Direct Remote ID standard. Additional information and usage of these messages is documented at <https://mavlink.io/en/services/opendroneid.html>."]
21640#[derive(Debug, Clone, PartialEq)]
21641#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21642#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21643pub struct OPEN_DRONE_ID_BASIC_ID_DATA {
21644 #[doc = "System ID (0 for broadcast)."]
21645 pub target_system: u8,
21646 #[doc = "Component ID (0 for broadcast)."]
21647 pub target_component: u8,
21648 #[doc = "Only used for drone ID data received from other UAs. See detailed description at <https://mavlink.io/en/services/opendroneid.html>."]
21649 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
21650 pub id_or_mac: [u8; 20],
21651 #[doc = "Indicates the format for the uas_id field of this message."]
21652 pub id_type: MavOdidIdType,
21653 #[doc = "Indicates the type of UA (Unmanned Aircraft)."]
21654 pub ua_type: MavOdidUaType,
21655 #[doc = "UAS (Unmanned Aircraft System) ID following the format specified by id_type. Shall be filled with nulls in the unused portion of the field."]
21656 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
21657 pub uas_id: [u8; 20],
21658}
21659impl OPEN_DRONE_ID_BASIC_ID_DATA {
21660 pub const ENCODED_LEN: usize = 44usize;
21661 pub const DEFAULT: Self = Self {
21662 target_system: 0_u8,
21663 target_component: 0_u8,
21664 id_or_mac: [0_u8; 20usize],
21665 id_type: MavOdidIdType::DEFAULT,
21666 ua_type: MavOdidUaType::DEFAULT,
21667 uas_id: [0_u8; 20usize],
21668 };
21669 #[cfg(feature = "arbitrary")]
21670 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
21671 use arbitrary::{Arbitrary, Unstructured};
21672 let mut buf = [0u8; 1024];
21673 rng.fill_bytes(&mut buf);
21674 let mut unstructured = Unstructured::new(&buf);
21675 Self::arbitrary(&mut unstructured).unwrap_or_default()
21676 }
21677}
21678impl Default for OPEN_DRONE_ID_BASIC_ID_DATA {
21679 fn default() -> Self {
21680 Self::DEFAULT.clone()
21681 }
21682}
21683impl MessageData for OPEN_DRONE_ID_BASIC_ID_DATA {
21684 type Message = MavMessage;
21685 const ID: u32 = 12900u32;
21686 const NAME: &'static str = "OPEN_DRONE_ID_BASIC_ID";
21687 const EXTRA_CRC: u8 = 114u8;
21688 const ENCODED_LEN: usize = 44usize;
21689 fn deser(
21690 _version: MavlinkVersion,
21691 __input: &[u8],
21692 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21693 let avail_len = __input.len();
21694 let mut payload_buf = [0; Self::ENCODED_LEN];
21695 let mut buf = if avail_len < Self::ENCODED_LEN {
21696 payload_buf[0..avail_len].copy_from_slice(__input);
21697 Bytes::new(&payload_buf)
21698 } else {
21699 Bytes::new(__input)
21700 };
21701 let mut __struct = Self::default();
21702 __struct.target_system = buf.get_u8();
21703 __struct.target_component = buf.get_u8();
21704 for v in &mut __struct.id_or_mac {
21705 let val = buf.get_u8();
21706 *v = val;
21707 }
21708 let tmp = buf.get_u8();
21709 __struct.id_type =
21710 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
21711 enum_type: "MavOdidIdType",
21712 value: tmp as u32,
21713 })?;
21714 let tmp = buf.get_u8();
21715 __struct.ua_type =
21716 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
21717 enum_type: "MavOdidUaType",
21718 value: tmp as u32,
21719 })?;
21720 for v in &mut __struct.uas_id {
21721 let val = buf.get_u8();
21722 *v = val;
21723 }
21724 Ok(__struct)
21725 }
21726 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21727 let mut __tmp = BytesMut::new(bytes);
21728 #[allow(clippy::absurd_extreme_comparisons)]
21729 #[allow(unused_comparisons)]
21730 if __tmp.remaining() < Self::ENCODED_LEN {
21731 panic!(
21732 "buffer is too small (need {} bytes, but got {})",
21733 Self::ENCODED_LEN,
21734 __tmp.remaining(),
21735 )
21736 }
21737 __tmp.put_u8(self.target_system);
21738 __tmp.put_u8(self.target_component);
21739 for val in &self.id_or_mac {
21740 __tmp.put_u8(*val);
21741 }
21742 __tmp.put_u8(self.id_type as u8);
21743 __tmp.put_u8(self.ua_type as u8);
21744 for val in &self.uas_id {
21745 __tmp.put_u8(*val);
21746 }
21747 if matches!(version, MavlinkVersion::V2) {
21748 let len = __tmp.len();
21749 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21750 } else {
21751 __tmp.len()
21752 }
21753 }
21754}
21755#[doc = "id: 137"]
21756#[doc = "Barometer readings for 2nd barometer."]
21757#[derive(Debug, Clone, PartialEq)]
21758#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21759#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21760pub struct SCALED_PRESSURE2_DATA {
21761 #[doc = "Timestamp (time since system boot)."]
21762 pub time_boot_ms: u32,
21763 #[doc = "Absolute pressure"]
21764 pub press_abs: f32,
21765 #[doc = "Differential pressure"]
21766 pub press_diff: f32,
21767 #[doc = "Absolute pressure temperature"]
21768 pub temperature: i16,
21769 #[doc = "Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC."]
21770 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
21771 pub temperature_press_diff: i16,
21772}
21773impl SCALED_PRESSURE2_DATA {
21774 pub const ENCODED_LEN: usize = 16usize;
21775 pub const DEFAULT: Self = Self {
21776 time_boot_ms: 0_u32,
21777 press_abs: 0.0_f32,
21778 press_diff: 0.0_f32,
21779 temperature: 0_i16,
21780 temperature_press_diff: 0_i16,
21781 };
21782 #[cfg(feature = "arbitrary")]
21783 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
21784 use arbitrary::{Arbitrary, Unstructured};
21785 let mut buf = [0u8; 1024];
21786 rng.fill_bytes(&mut buf);
21787 let mut unstructured = Unstructured::new(&buf);
21788 Self::arbitrary(&mut unstructured).unwrap_or_default()
21789 }
21790}
21791impl Default for SCALED_PRESSURE2_DATA {
21792 fn default() -> Self {
21793 Self::DEFAULT.clone()
21794 }
21795}
21796impl MessageData for SCALED_PRESSURE2_DATA {
21797 type Message = MavMessage;
21798 const ID: u32 = 137u32;
21799 const NAME: &'static str = "SCALED_PRESSURE2";
21800 const EXTRA_CRC: u8 = 195u8;
21801 const ENCODED_LEN: usize = 16usize;
21802 fn deser(
21803 _version: MavlinkVersion,
21804 __input: &[u8],
21805 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21806 let avail_len = __input.len();
21807 let mut payload_buf = [0; Self::ENCODED_LEN];
21808 let mut buf = if avail_len < Self::ENCODED_LEN {
21809 payload_buf[0..avail_len].copy_from_slice(__input);
21810 Bytes::new(&payload_buf)
21811 } else {
21812 Bytes::new(__input)
21813 };
21814 let mut __struct = Self::default();
21815 __struct.time_boot_ms = buf.get_u32_le();
21816 __struct.press_abs = buf.get_f32_le();
21817 __struct.press_diff = buf.get_f32_le();
21818 __struct.temperature = buf.get_i16_le();
21819 __struct.temperature_press_diff = buf.get_i16_le();
21820 Ok(__struct)
21821 }
21822 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21823 let mut __tmp = BytesMut::new(bytes);
21824 #[allow(clippy::absurd_extreme_comparisons)]
21825 #[allow(unused_comparisons)]
21826 if __tmp.remaining() < Self::ENCODED_LEN {
21827 panic!(
21828 "buffer is too small (need {} bytes, but got {})",
21829 Self::ENCODED_LEN,
21830 __tmp.remaining(),
21831 )
21832 }
21833 __tmp.put_u32_le(self.time_boot_ms);
21834 __tmp.put_f32_le(self.press_abs);
21835 __tmp.put_f32_le(self.press_diff);
21836 __tmp.put_i16_le(self.temperature);
21837 __tmp.put_i16_le(self.temperature_press_diff);
21838 if matches!(version, MavlinkVersion::V2) {
21839 let len = __tmp.len();
21840 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21841 } else {
21842 __tmp.len()
21843 }
21844 }
21845}
21846#[doc = "id: 149"]
21847#[doc = "The location of a landing target. See: <https://mavlink.io/en/services/landing_target.html>."]
21848#[derive(Debug, Clone, PartialEq)]
21849#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21850#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21851pub struct LANDING_TARGET_DATA {
21852 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
21853 pub time_usec: u64,
21854 #[doc = "X-axis angular offset of the target from the center of the image"]
21855 pub angle_x: f32,
21856 #[doc = "Y-axis angular offset of the target from the center of the image"]
21857 pub angle_y: f32,
21858 #[doc = "Distance to the target from the vehicle"]
21859 pub distance: f32,
21860 #[doc = "Size of target along x-axis"]
21861 pub size_x: f32,
21862 #[doc = "Size of target along y-axis"]
21863 pub size_y: f32,
21864 #[doc = "The ID of the target if multiple targets are present"]
21865 pub target_num: u8,
21866 #[doc = "Coordinate frame used for following fields."]
21867 pub frame: MavFrame,
21868 #[doc = "X Position of the landing target in MAV_FRAME"]
21869 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
21870 pub x: f32,
21871 #[doc = "Y Position of the landing target in MAV_FRAME"]
21872 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
21873 pub y: f32,
21874 #[doc = "Z Position of the landing target in MAV_FRAME"]
21875 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
21876 pub z: f32,
21877 #[doc = "Quaternion of landing target orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)"]
21878 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
21879 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
21880 pub q: [f32; 4],
21881 #[doc = "Type of landing target"]
21882 #[cfg_attr(feature = "serde", serde(default))]
21883 pub mavtype: LandingTargetType,
21884 #[doc = "Boolean indicating whether the position fields (x, y, z, q, type) contain valid target position information (valid: 1, invalid: 0). Default is 0 (invalid)."]
21885 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
21886 pub position_valid: u8,
21887}
21888impl LANDING_TARGET_DATA {
21889 pub const ENCODED_LEN: usize = 60usize;
21890 pub const DEFAULT: Self = Self {
21891 time_usec: 0_u64,
21892 angle_x: 0.0_f32,
21893 angle_y: 0.0_f32,
21894 distance: 0.0_f32,
21895 size_x: 0.0_f32,
21896 size_y: 0.0_f32,
21897 target_num: 0_u8,
21898 frame: MavFrame::DEFAULT,
21899 x: 0.0_f32,
21900 y: 0.0_f32,
21901 z: 0.0_f32,
21902 q: [0.0_f32; 4usize],
21903 mavtype: LandingTargetType::DEFAULT,
21904 position_valid: 0_u8,
21905 };
21906 #[cfg(feature = "arbitrary")]
21907 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
21908 use arbitrary::{Arbitrary, Unstructured};
21909 let mut buf = [0u8; 1024];
21910 rng.fill_bytes(&mut buf);
21911 let mut unstructured = Unstructured::new(&buf);
21912 Self::arbitrary(&mut unstructured).unwrap_or_default()
21913 }
21914}
21915impl Default for LANDING_TARGET_DATA {
21916 fn default() -> Self {
21917 Self::DEFAULT.clone()
21918 }
21919}
21920impl MessageData for LANDING_TARGET_DATA {
21921 type Message = MavMessage;
21922 const ID: u32 = 149u32;
21923 const NAME: &'static str = "LANDING_TARGET";
21924 const EXTRA_CRC: u8 = 200u8;
21925 const ENCODED_LEN: usize = 60usize;
21926 fn deser(
21927 _version: MavlinkVersion,
21928 __input: &[u8],
21929 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21930 let avail_len = __input.len();
21931 let mut payload_buf = [0; Self::ENCODED_LEN];
21932 let mut buf = if avail_len < Self::ENCODED_LEN {
21933 payload_buf[0..avail_len].copy_from_slice(__input);
21934 Bytes::new(&payload_buf)
21935 } else {
21936 Bytes::new(__input)
21937 };
21938 let mut __struct = Self::default();
21939 __struct.time_usec = buf.get_u64_le();
21940 __struct.angle_x = buf.get_f32_le();
21941 __struct.angle_y = buf.get_f32_le();
21942 __struct.distance = buf.get_f32_le();
21943 __struct.size_x = buf.get_f32_le();
21944 __struct.size_y = buf.get_f32_le();
21945 __struct.target_num = buf.get_u8();
21946 let tmp = buf.get_u8();
21947 __struct.frame =
21948 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
21949 enum_type: "MavFrame",
21950 value: tmp as u32,
21951 })?;
21952 __struct.x = buf.get_f32_le();
21953 __struct.y = buf.get_f32_le();
21954 __struct.z = buf.get_f32_le();
21955 for v in &mut __struct.q {
21956 let val = buf.get_f32_le();
21957 *v = val;
21958 }
21959 let tmp = buf.get_u8();
21960 __struct.mavtype =
21961 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
21962 enum_type: "LandingTargetType",
21963 value: tmp as u32,
21964 })?;
21965 __struct.position_valid = buf.get_u8();
21966 Ok(__struct)
21967 }
21968 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21969 let mut __tmp = BytesMut::new(bytes);
21970 #[allow(clippy::absurd_extreme_comparisons)]
21971 #[allow(unused_comparisons)]
21972 if __tmp.remaining() < Self::ENCODED_LEN {
21973 panic!(
21974 "buffer is too small (need {} bytes, but got {})",
21975 Self::ENCODED_LEN,
21976 __tmp.remaining(),
21977 )
21978 }
21979 __tmp.put_u64_le(self.time_usec);
21980 __tmp.put_f32_le(self.angle_x);
21981 __tmp.put_f32_le(self.angle_y);
21982 __tmp.put_f32_le(self.distance);
21983 __tmp.put_f32_le(self.size_x);
21984 __tmp.put_f32_le(self.size_y);
21985 __tmp.put_u8(self.target_num);
21986 __tmp.put_u8(self.frame as u8);
21987 __tmp.put_f32_le(self.x);
21988 __tmp.put_f32_le(self.y);
21989 __tmp.put_f32_le(self.z);
21990 for val in &self.q {
21991 __tmp.put_f32_le(*val);
21992 }
21993 __tmp.put_u8(self.mavtype as u8);
21994 __tmp.put_u8(self.position_valid);
21995 if matches!(version, MavlinkVersion::V2) {
21996 let len = __tmp.len();
21997 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21998 } else {
21999 __tmp.len()
22000 }
22001 }
22002}
22003#[doc = "id: 12919"]
22004#[doc = "Update the data in the OPEN_DRONE_ID_SYSTEM message with new location information. This can be sent to update the location information for the operator when no other information in the SYSTEM message has changed. This message allows for efficient operation on radio links which have limited uplink bandwidth while meeting requirements for update frequency of the operator location."]
22005#[derive(Debug, Clone, PartialEq)]
22006#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22007#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22008pub struct OPEN_DRONE_ID_SYSTEM_UPDATE_DATA {
22009 #[doc = "Latitude of the operator. If unknown: 0 (both Lat/Lon)."]
22010 pub operator_latitude: i32,
22011 #[doc = "Longitude of the operator. If unknown: 0 (both Lat/Lon)."]
22012 pub operator_longitude: i32,
22013 #[doc = "Geodetic altitude of the operator relative to WGS84. If unknown: -1000 m."]
22014 pub operator_altitude_geo: f32,
22015 #[doc = "32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019."]
22016 pub timestamp: u32,
22017 #[doc = "System ID (0 for broadcast)."]
22018 pub target_system: u8,
22019 #[doc = "Component ID (0 for broadcast)."]
22020 pub target_component: u8,
22021}
22022impl OPEN_DRONE_ID_SYSTEM_UPDATE_DATA {
22023 pub const ENCODED_LEN: usize = 18usize;
22024 pub const DEFAULT: Self = Self {
22025 operator_latitude: 0_i32,
22026 operator_longitude: 0_i32,
22027 operator_altitude_geo: 0.0_f32,
22028 timestamp: 0_u32,
22029 target_system: 0_u8,
22030 target_component: 0_u8,
22031 };
22032 #[cfg(feature = "arbitrary")]
22033 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22034 use arbitrary::{Arbitrary, Unstructured};
22035 let mut buf = [0u8; 1024];
22036 rng.fill_bytes(&mut buf);
22037 let mut unstructured = Unstructured::new(&buf);
22038 Self::arbitrary(&mut unstructured).unwrap_or_default()
22039 }
22040}
22041impl Default for OPEN_DRONE_ID_SYSTEM_UPDATE_DATA {
22042 fn default() -> Self {
22043 Self::DEFAULT.clone()
22044 }
22045}
22046impl MessageData for OPEN_DRONE_ID_SYSTEM_UPDATE_DATA {
22047 type Message = MavMessage;
22048 const ID: u32 = 12919u32;
22049 const NAME: &'static str = "OPEN_DRONE_ID_SYSTEM_UPDATE";
22050 const EXTRA_CRC: u8 = 7u8;
22051 const ENCODED_LEN: usize = 18usize;
22052 fn deser(
22053 _version: MavlinkVersion,
22054 __input: &[u8],
22055 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22056 let avail_len = __input.len();
22057 let mut payload_buf = [0; Self::ENCODED_LEN];
22058 let mut buf = if avail_len < Self::ENCODED_LEN {
22059 payload_buf[0..avail_len].copy_from_slice(__input);
22060 Bytes::new(&payload_buf)
22061 } else {
22062 Bytes::new(__input)
22063 };
22064 let mut __struct = Self::default();
22065 __struct.operator_latitude = buf.get_i32_le();
22066 __struct.operator_longitude = buf.get_i32_le();
22067 __struct.operator_altitude_geo = buf.get_f32_le();
22068 __struct.timestamp = buf.get_u32_le();
22069 __struct.target_system = buf.get_u8();
22070 __struct.target_component = buf.get_u8();
22071 Ok(__struct)
22072 }
22073 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22074 let mut __tmp = BytesMut::new(bytes);
22075 #[allow(clippy::absurd_extreme_comparisons)]
22076 #[allow(unused_comparisons)]
22077 if __tmp.remaining() < Self::ENCODED_LEN {
22078 panic!(
22079 "buffer is too small (need {} bytes, but got {})",
22080 Self::ENCODED_LEN,
22081 __tmp.remaining(),
22082 )
22083 }
22084 __tmp.put_i32_le(self.operator_latitude);
22085 __tmp.put_i32_le(self.operator_longitude);
22086 __tmp.put_f32_le(self.operator_altitude_geo);
22087 __tmp.put_u32_le(self.timestamp);
22088 __tmp.put_u8(self.target_system);
22089 __tmp.put_u8(self.target_component);
22090 if matches!(version, MavlinkVersion::V2) {
22091 let len = __tmp.len();
22092 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22093 } else {
22094 __tmp.len()
22095 }
22096 }
22097}
22098#[doc = "id: 37"]
22099#[doc = "Request a partial list of mission items from the system/component. <https://mavlink.io/en/services/mission.html>. If start and end index are the same, just send one waypoint."]
22100#[derive(Debug, Clone, PartialEq)]
22101#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22102#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22103pub struct MISSION_REQUEST_PARTIAL_LIST_DATA {
22104 #[doc = "Start index"]
22105 pub start_index: i16,
22106 #[doc = "End index, -1 by default (-1: send list to end). Else a valid index of the list"]
22107 pub end_index: i16,
22108 #[doc = "System ID"]
22109 pub target_system: u8,
22110 #[doc = "Component ID"]
22111 pub target_component: u8,
22112 #[doc = "Mission type."]
22113 #[cfg_attr(feature = "serde", serde(default))]
22114 pub mission_type: MavMissionType,
22115}
22116impl MISSION_REQUEST_PARTIAL_LIST_DATA {
22117 pub const ENCODED_LEN: usize = 7usize;
22118 pub const DEFAULT: Self = Self {
22119 start_index: 0_i16,
22120 end_index: 0_i16,
22121 target_system: 0_u8,
22122 target_component: 0_u8,
22123 mission_type: MavMissionType::DEFAULT,
22124 };
22125 #[cfg(feature = "arbitrary")]
22126 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22127 use arbitrary::{Arbitrary, Unstructured};
22128 let mut buf = [0u8; 1024];
22129 rng.fill_bytes(&mut buf);
22130 let mut unstructured = Unstructured::new(&buf);
22131 Self::arbitrary(&mut unstructured).unwrap_or_default()
22132 }
22133}
22134impl Default for MISSION_REQUEST_PARTIAL_LIST_DATA {
22135 fn default() -> Self {
22136 Self::DEFAULT.clone()
22137 }
22138}
22139impl MessageData for MISSION_REQUEST_PARTIAL_LIST_DATA {
22140 type Message = MavMessage;
22141 const ID: u32 = 37u32;
22142 const NAME: &'static str = "MISSION_REQUEST_PARTIAL_LIST";
22143 const EXTRA_CRC: u8 = 212u8;
22144 const ENCODED_LEN: usize = 7usize;
22145 fn deser(
22146 _version: MavlinkVersion,
22147 __input: &[u8],
22148 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22149 let avail_len = __input.len();
22150 let mut payload_buf = [0; Self::ENCODED_LEN];
22151 let mut buf = if avail_len < Self::ENCODED_LEN {
22152 payload_buf[0..avail_len].copy_from_slice(__input);
22153 Bytes::new(&payload_buf)
22154 } else {
22155 Bytes::new(__input)
22156 };
22157 let mut __struct = Self::default();
22158 __struct.start_index = buf.get_i16_le();
22159 __struct.end_index = buf.get_i16_le();
22160 __struct.target_system = buf.get_u8();
22161 __struct.target_component = buf.get_u8();
22162 let tmp = buf.get_u8();
22163 __struct.mission_type =
22164 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
22165 enum_type: "MavMissionType",
22166 value: tmp as u32,
22167 })?;
22168 Ok(__struct)
22169 }
22170 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22171 let mut __tmp = BytesMut::new(bytes);
22172 #[allow(clippy::absurd_extreme_comparisons)]
22173 #[allow(unused_comparisons)]
22174 if __tmp.remaining() < Self::ENCODED_LEN {
22175 panic!(
22176 "buffer is too small (need {} bytes, but got {})",
22177 Self::ENCODED_LEN,
22178 __tmp.remaining(),
22179 )
22180 }
22181 __tmp.put_i16_le(self.start_index);
22182 __tmp.put_i16_le(self.end_index);
22183 __tmp.put_u8(self.target_system);
22184 __tmp.put_u8(self.target_component);
22185 __tmp.put_u8(self.mission_type as u8);
22186 if matches!(version, MavlinkVersion::V2) {
22187 let len = __tmp.len();
22188 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22189 } else {
22190 __tmp.len()
22191 }
22192 }
22193}
22194#[doc = "id: 74"]
22195#[doc = "Metrics typically displayed on a HUD for fixed wing aircraft."]
22196#[derive(Debug, Clone, PartialEq)]
22197#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22198#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22199pub struct VFR_HUD_DATA {
22200 #[doc = "Vehicle speed in form appropriate for vehicle type. For standard aircraft this is typically calibrated airspeed (CAS) or indicated airspeed (IAS) - either of which can be used by a pilot to estimate stall speed."]
22201 pub airspeed: f32,
22202 #[doc = "Current ground speed."]
22203 pub groundspeed: f32,
22204 #[doc = "Current altitude (MSL)."]
22205 pub alt: f32,
22206 #[doc = "Current climb rate."]
22207 pub climb: f32,
22208 #[doc = "Current heading in compass units (0-360, 0=north)."]
22209 pub heading: i16,
22210 #[doc = "Current throttle setting (0 to 100)."]
22211 pub throttle: u16,
22212}
22213impl VFR_HUD_DATA {
22214 pub const ENCODED_LEN: usize = 20usize;
22215 pub const DEFAULT: Self = Self {
22216 airspeed: 0.0_f32,
22217 groundspeed: 0.0_f32,
22218 alt: 0.0_f32,
22219 climb: 0.0_f32,
22220 heading: 0_i16,
22221 throttle: 0_u16,
22222 };
22223 #[cfg(feature = "arbitrary")]
22224 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22225 use arbitrary::{Arbitrary, Unstructured};
22226 let mut buf = [0u8; 1024];
22227 rng.fill_bytes(&mut buf);
22228 let mut unstructured = Unstructured::new(&buf);
22229 Self::arbitrary(&mut unstructured).unwrap_or_default()
22230 }
22231}
22232impl Default for VFR_HUD_DATA {
22233 fn default() -> Self {
22234 Self::DEFAULT.clone()
22235 }
22236}
22237impl MessageData for VFR_HUD_DATA {
22238 type Message = MavMessage;
22239 const ID: u32 = 74u32;
22240 const NAME: &'static str = "VFR_HUD";
22241 const EXTRA_CRC: u8 = 20u8;
22242 const ENCODED_LEN: usize = 20usize;
22243 fn deser(
22244 _version: MavlinkVersion,
22245 __input: &[u8],
22246 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22247 let avail_len = __input.len();
22248 let mut payload_buf = [0; Self::ENCODED_LEN];
22249 let mut buf = if avail_len < Self::ENCODED_LEN {
22250 payload_buf[0..avail_len].copy_from_slice(__input);
22251 Bytes::new(&payload_buf)
22252 } else {
22253 Bytes::new(__input)
22254 };
22255 let mut __struct = Self::default();
22256 __struct.airspeed = buf.get_f32_le();
22257 __struct.groundspeed = buf.get_f32_le();
22258 __struct.alt = buf.get_f32_le();
22259 __struct.climb = buf.get_f32_le();
22260 __struct.heading = buf.get_i16_le();
22261 __struct.throttle = buf.get_u16_le();
22262 Ok(__struct)
22263 }
22264 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22265 let mut __tmp = BytesMut::new(bytes);
22266 #[allow(clippy::absurd_extreme_comparisons)]
22267 #[allow(unused_comparisons)]
22268 if __tmp.remaining() < Self::ENCODED_LEN {
22269 panic!(
22270 "buffer is too small (need {} bytes, but got {})",
22271 Self::ENCODED_LEN,
22272 __tmp.remaining(),
22273 )
22274 }
22275 __tmp.put_f32_le(self.airspeed);
22276 __tmp.put_f32_le(self.groundspeed);
22277 __tmp.put_f32_le(self.alt);
22278 __tmp.put_f32_le(self.climb);
22279 __tmp.put_i16_le(self.heading);
22280 __tmp.put_u16_le(self.throttle);
22281 if matches!(version, MavlinkVersion::V2) {
22282 let len = __tmp.len();
22283 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22284 } else {
22285 __tmp.len()
22286 }
22287 }
22288}
22289#[doc = "id: 1"]
22290#[doc = "The general system state. If the system is following the MAVLink standard, the system state is mainly defined by three orthogonal states/modes: The system mode, which is either LOCKED (motors shut down and locked), MANUAL (system under RC control), GUIDED (system with autonomous position control, position setpoint controlled manually) or AUTO (system guided by path/waypoint planner). The NAV_MODE defined the current flight state: LIFTOFF (often an open-loop maneuver), LANDING, WAYPOINTS or VECTOR. This represents the internal navigation state machine. The system status shows whether the system is currently active or not and if an emergency occurred. During the CRITICAL and EMERGENCY states the MAV is still considered to be active, but should start emergency procedures autonomously. After a failure occurred it should first move from active to critical to allow manual intervention and then move to emergency after a certain timeout."]
22291#[derive(Debug, Clone, PartialEq)]
22292#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22293#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22294pub struct SYS_STATUS_DATA {
22295 #[doc = "Bitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present."]
22296 pub onboard_control_sensors_present: MavSysStatusSensor,
22297 #[doc = "Bitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled."]
22298 pub onboard_control_sensors_enabled: MavSysStatusSensor,
22299 #[doc = "Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy."]
22300 pub onboard_control_sensors_health: MavSysStatusSensor,
22301 #[doc = "Maximum usage in percent of the mainloop time. Values: [0-1000] - should always be below 1000"]
22302 pub load: u16,
22303 #[doc = "Battery voltage, UINT16_MAX: Voltage not sent by autopilot"]
22304 pub voltage_battery: u16,
22305 #[doc = "Battery current, -1: Current not sent by autopilot"]
22306 pub current_battery: i16,
22307 #[doc = "Communication drop rate, (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)"]
22308 pub drop_rate_comm: u16,
22309 #[doc = "Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)"]
22310 pub errors_comm: u16,
22311 #[doc = "Autopilot-specific errors"]
22312 pub errors_count1: u16,
22313 #[doc = "Autopilot-specific errors"]
22314 pub errors_count2: u16,
22315 #[doc = "Autopilot-specific errors"]
22316 pub errors_count3: u16,
22317 #[doc = "Autopilot-specific errors"]
22318 pub errors_count4: u16,
22319 #[doc = "Battery energy remaining, -1: Battery remaining energy not sent by autopilot"]
22320 pub battery_remaining: i8,
22321 #[doc = "Bitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present."]
22322 #[cfg_attr(feature = "serde", serde(default))]
22323 pub onboard_control_sensors_present_extended: MavSysStatusSensorExtended,
22324 #[doc = "Bitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled."]
22325 #[cfg_attr(feature = "serde", serde(default))]
22326 pub onboard_control_sensors_enabled_extended: MavSysStatusSensorExtended,
22327 #[doc = "Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy."]
22328 #[cfg_attr(feature = "serde", serde(default))]
22329 pub onboard_control_sensors_health_extended: MavSysStatusSensorExtended,
22330}
22331impl SYS_STATUS_DATA {
22332 pub const ENCODED_LEN: usize = 43usize;
22333 pub const DEFAULT: Self = Self {
22334 onboard_control_sensors_present: MavSysStatusSensor::DEFAULT,
22335 onboard_control_sensors_enabled: MavSysStatusSensor::DEFAULT,
22336 onboard_control_sensors_health: MavSysStatusSensor::DEFAULT,
22337 load: 0_u16,
22338 voltage_battery: 0_u16,
22339 current_battery: 0_i16,
22340 drop_rate_comm: 0_u16,
22341 errors_comm: 0_u16,
22342 errors_count1: 0_u16,
22343 errors_count2: 0_u16,
22344 errors_count3: 0_u16,
22345 errors_count4: 0_u16,
22346 battery_remaining: 0_i8,
22347 onboard_control_sensors_present_extended: MavSysStatusSensorExtended::DEFAULT,
22348 onboard_control_sensors_enabled_extended: MavSysStatusSensorExtended::DEFAULT,
22349 onboard_control_sensors_health_extended: MavSysStatusSensorExtended::DEFAULT,
22350 };
22351 #[cfg(feature = "arbitrary")]
22352 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22353 use arbitrary::{Arbitrary, Unstructured};
22354 let mut buf = [0u8; 1024];
22355 rng.fill_bytes(&mut buf);
22356 let mut unstructured = Unstructured::new(&buf);
22357 Self::arbitrary(&mut unstructured).unwrap_or_default()
22358 }
22359}
22360impl Default for SYS_STATUS_DATA {
22361 fn default() -> Self {
22362 Self::DEFAULT.clone()
22363 }
22364}
22365impl MessageData for SYS_STATUS_DATA {
22366 type Message = MavMessage;
22367 const ID: u32 = 1u32;
22368 const NAME: &'static str = "SYS_STATUS";
22369 const EXTRA_CRC: u8 = 124u8;
22370 const ENCODED_LEN: usize = 43usize;
22371 fn deser(
22372 _version: MavlinkVersion,
22373 __input: &[u8],
22374 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22375 let avail_len = __input.len();
22376 let mut payload_buf = [0; Self::ENCODED_LEN];
22377 let mut buf = if avail_len < Self::ENCODED_LEN {
22378 payload_buf[0..avail_len].copy_from_slice(__input);
22379 Bytes::new(&payload_buf)
22380 } else {
22381 Bytes::new(__input)
22382 };
22383 let mut __struct = Self::default();
22384 let tmp = buf.get_u32_le();
22385 __struct.onboard_control_sensors_present = MavSysStatusSensor::from_bits(
22386 tmp & MavSysStatusSensor::all().bits(),
22387 )
22388 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
22389 flag_type: "MavSysStatusSensor",
22390 value: tmp as u32,
22391 })?;
22392 let tmp = buf.get_u32_le();
22393 __struct.onboard_control_sensors_enabled = MavSysStatusSensor::from_bits(
22394 tmp & MavSysStatusSensor::all().bits(),
22395 )
22396 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
22397 flag_type: "MavSysStatusSensor",
22398 value: tmp as u32,
22399 })?;
22400 let tmp = buf.get_u32_le();
22401 __struct.onboard_control_sensors_health = MavSysStatusSensor::from_bits(
22402 tmp & MavSysStatusSensor::all().bits(),
22403 )
22404 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
22405 flag_type: "MavSysStatusSensor",
22406 value: tmp as u32,
22407 })?;
22408 __struct.load = buf.get_u16_le();
22409 __struct.voltage_battery = buf.get_u16_le();
22410 __struct.current_battery = buf.get_i16_le();
22411 __struct.drop_rate_comm = buf.get_u16_le();
22412 __struct.errors_comm = buf.get_u16_le();
22413 __struct.errors_count1 = buf.get_u16_le();
22414 __struct.errors_count2 = buf.get_u16_le();
22415 __struct.errors_count3 = buf.get_u16_le();
22416 __struct.errors_count4 = buf.get_u16_le();
22417 __struct.battery_remaining = buf.get_i8();
22418 let tmp = buf.get_u32_le();
22419 __struct.onboard_control_sensors_present_extended =
22420 MavSysStatusSensorExtended::from_bits(tmp & MavSysStatusSensorExtended::all().bits())
22421 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
22422 flag_type: "MavSysStatusSensorExtended",
22423 value: tmp as u32,
22424 })?;
22425 let tmp = buf.get_u32_le();
22426 __struct.onboard_control_sensors_enabled_extended =
22427 MavSysStatusSensorExtended::from_bits(tmp & MavSysStatusSensorExtended::all().bits())
22428 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
22429 flag_type: "MavSysStatusSensorExtended",
22430 value: tmp as u32,
22431 })?;
22432 let tmp = buf.get_u32_le();
22433 __struct.onboard_control_sensors_health_extended =
22434 MavSysStatusSensorExtended::from_bits(tmp & MavSysStatusSensorExtended::all().bits())
22435 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
22436 flag_type: "MavSysStatusSensorExtended",
22437 value: tmp as u32,
22438 })?;
22439 Ok(__struct)
22440 }
22441 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22442 let mut __tmp = BytesMut::new(bytes);
22443 #[allow(clippy::absurd_extreme_comparisons)]
22444 #[allow(unused_comparisons)]
22445 if __tmp.remaining() < Self::ENCODED_LEN {
22446 panic!(
22447 "buffer is too small (need {} bytes, but got {})",
22448 Self::ENCODED_LEN,
22449 __tmp.remaining(),
22450 )
22451 }
22452 __tmp.put_u32_le(self.onboard_control_sensors_present.bits());
22453 __tmp.put_u32_le(self.onboard_control_sensors_enabled.bits());
22454 __tmp.put_u32_le(self.onboard_control_sensors_health.bits());
22455 __tmp.put_u16_le(self.load);
22456 __tmp.put_u16_le(self.voltage_battery);
22457 __tmp.put_i16_le(self.current_battery);
22458 __tmp.put_u16_le(self.drop_rate_comm);
22459 __tmp.put_u16_le(self.errors_comm);
22460 __tmp.put_u16_le(self.errors_count1);
22461 __tmp.put_u16_le(self.errors_count2);
22462 __tmp.put_u16_le(self.errors_count3);
22463 __tmp.put_u16_le(self.errors_count4);
22464 __tmp.put_i8(self.battery_remaining);
22465 __tmp.put_u32_le(self.onboard_control_sensors_present_extended.bits());
22466 __tmp.put_u32_le(self.onboard_control_sensors_enabled_extended.bits());
22467 __tmp.put_u32_le(self.onboard_control_sensors_health_extended.bits());
22468 if matches!(version, MavlinkVersion::V2) {
22469 let len = __tmp.len();
22470 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22471 } else {
22472 __tmp.len()
22473 }
22474 }
22475}
22476#[doc = "id: 49"]
22477#[doc = "Publishes the GPS coordinates of the vehicle local origin (0,0,0) position. Emitted whenever a new GPS-Local position mapping is requested or set - e.g. following SET_GPS_GLOBAL_ORIGIN message."]
22478#[derive(Debug, Clone, PartialEq)]
22479#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22480#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22481pub struct GPS_GLOBAL_ORIGIN_DATA {
22482 #[doc = "Latitude (WGS84)"]
22483 pub latitude: i32,
22484 #[doc = "Longitude (WGS84)"]
22485 pub longitude: i32,
22486 #[doc = "Altitude (MSL). Positive for up."]
22487 pub altitude: i32,
22488 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
22489 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
22490 pub time_usec: u64,
22491}
22492impl GPS_GLOBAL_ORIGIN_DATA {
22493 pub const ENCODED_LEN: usize = 20usize;
22494 pub const DEFAULT: Self = Self {
22495 latitude: 0_i32,
22496 longitude: 0_i32,
22497 altitude: 0_i32,
22498 time_usec: 0_u64,
22499 };
22500 #[cfg(feature = "arbitrary")]
22501 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22502 use arbitrary::{Arbitrary, Unstructured};
22503 let mut buf = [0u8; 1024];
22504 rng.fill_bytes(&mut buf);
22505 let mut unstructured = Unstructured::new(&buf);
22506 Self::arbitrary(&mut unstructured).unwrap_or_default()
22507 }
22508}
22509impl Default for GPS_GLOBAL_ORIGIN_DATA {
22510 fn default() -> Self {
22511 Self::DEFAULT.clone()
22512 }
22513}
22514impl MessageData for GPS_GLOBAL_ORIGIN_DATA {
22515 type Message = MavMessage;
22516 const ID: u32 = 49u32;
22517 const NAME: &'static str = "GPS_GLOBAL_ORIGIN";
22518 const EXTRA_CRC: u8 = 39u8;
22519 const ENCODED_LEN: usize = 20usize;
22520 fn deser(
22521 _version: MavlinkVersion,
22522 __input: &[u8],
22523 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22524 let avail_len = __input.len();
22525 let mut payload_buf = [0; Self::ENCODED_LEN];
22526 let mut buf = if avail_len < Self::ENCODED_LEN {
22527 payload_buf[0..avail_len].copy_from_slice(__input);
22528 Bytes::new(&payload_buf)
22529 } else {
22530 Bytes::new(__input)
22531 };
22532 let mut __struct = Self::default();
22533 __struct.latitude = buf.get_i32_le();
22534 __struct.longitude = buf.get_i32_le();
22535 __struct.altitude = buf.get_i32_le();
22536 __struct.time_usec = buf.get_u64_le();
22537 Ok(__struct)
22538 }
22539 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22540 let mut __tmp = BytesMut::new(bytes);
22541 #[allow(clippy::absurd_extreme_comparisons)]
22542 #[allow(unused_comparisons)]
22543 if __tmp.remaining() < Self::ENCODED_LEN {
22544 panic!(
22545 "buffer is too small (need {} bytes, but got {})",
22546 Self::ENCODED_LEN,
22547 __tmp.remaining(),
22548 )
22549 }
22550 __tmp.put_i32_le(self.latitude);
22551 __tmp.put_i32_le(self.longitude);
22552 __tmp.put_i32_le(self.altitude);
22553 __tmp.put_u64_le(self.time_usec);
22554 if matches!(version, MavlinkVersion::V2) {
22555 let len = __tmp.len();
22556 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22557 } else {
22558 __tmp.len()
22559 }
22560 }
22561}
22562#[doc = "id: 281"]
22563#[doc = "Current status about a high level gimbal manager. This message should be broadcast at a low regular rate (e.g. 5Hz)."]
22564#[derive(Debug, Clone, PartialEq)]
22565#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22566#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22567pub struct GIMBAL_MANAGER_STATUS_DATA {
22568 #[doc = "Timestamp (time since system boot)."]
22569 pub time_boot_ms: u32,
22570 #[doc = "High level gimbal manager flags currently applied."]
22571 pub flags: GimbalManagerFlags,
22572 #[doc = "Gimbal device ID that this gimbal manager is responsible for. Component ID of gimbal device (or 1-6 for non-MAVLink gimbal)."]
22573 pub gimbal_device_id: u8,
22574 #[doc = "System ID of MAVLink component with primary control, 0 for none."]
22575 pub primary_control_sysid: u8,
22576 #[doc = "Component ID of MAVLink component with primary control, 0 for none."]
22577 pub primary_control_compid: u8,
22578 #[doc = "System ID of MAVLink component with secondary control, 0 for none."]
22579 pub secondary_control_sysid: u8,
22580 #[doc = "Component ID of MAVLink component with secondary control, 0 for none."]
22581 pub secondary_control_compid: u8,
22582}
22583impl GIMBAL_MANAGER_STATUS_DATA {
22584 pub const ENCODED_LEN: usize = 13usize;
22585 pub const DEFAULT: Self = Self {
22586 time_boot_ms: 0_u32,
22587 flags: GimbalManagerFlags::DEFAULT,
22588 gimbal_device_id: 0_u8,
22589 primary_control_sysid: 0_u8,
22590 primary_control_compid: 0_u8,
22591 secondary_control_sysid: 0_u8,
22592 secondary_control_compid: 0_u8,
22593 };
22594 #[cfg(feature = "arbitrary")]
22595 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22596 use arbitrary::{Arbitrary, Unstructured};
22597 let mut buf = [0u8; 1024];
22598 rng.fill_bytes(&mut buf);
22599 let mut unstructured = Unstructured::new(&buf);
22600 Self::arbitrary(&mut unstructured).unwrap_or_default()
22601 }
22602}
22603impl Default for GIMBAL_MANAGER_STATUS_DATA {
22604 fn default() -> Self {
22605 Self::DEFAULT.clone()
22606 }
22607}
22608impl MessageData for GIMBAL_MANAGER_STATUS_DATA {
22609 type Message = MavMessage;
22610 const ID: u32 = 281u32;
22611 const NAME: &'static str = "GIMBAL_MANAGER_STATUS";
22612 const EXTRA_CRC: u8 = 48u8;
22613 const ENCODED_LEN: usize = 13usize;
22614 fn deser(
22615 _version: MavlinkVersion,
22616 __input: &[u8],
22617 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22618 let avail_len = __input.len();
22619 let mut payload_buf = [0; Self::ENCODED_LEN];
22620 let mut buf = if avail_len < Self::ENCODED_LEN {
22621 payload_buf[0..avail_len].copy_from_slice(__input);
22622 Bytes::new(&payload_buf)
22623 } else {
22624 Bytes::new(__input)
22625 };
22626 let mut __struct = Self::default();
22627 __struct.time_boot_ms = buf.get_u32_le();
22628 let tmp = buf.get_u32_le();
22629 __struct.flags = GimbalManagerFlags::from_bits(tmp & GimbalManagerFlags::all().bits())
22630 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
22631 flag_type: "GimbalManagerFlags",
22632 value: tmp as u32,
22633 })?;
22634 __struct.gimbal_device_id = buf.get_u8();
22635 __struct.primary_control_sysid = buf.get_u8();
22636 __struct.primary_control_compid = buf.get_u8();
22637 __struct.secondary_control_sysid = buf.get_u8();
22638 __struct.secondary_control_compid = buf.get_u8();
22639 Ok(__struct)
22640 }
22641 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22642 let mut __tmp = BytesMut::new(bytes);
22643 #[allow(clippy::absurd_extreme_comparisons)]
22644 #[allow(unused_comparisons)]
22645 if __tmp.remaining() < Self::ENCODED_LEN {
22646 panic!(
22647 "buffer is too small (need {} bytes, but got {})",
22648 Self::ENCODED_LEN,
22649 __tmp.remaining(),
22650 )
22651 }
22652 __tmp.put_u32_le(self.time_boot_ms);
22653 __tmp.put_u32_le(self.flags.bits());
22654 __tmp.put_u8(self.gimbal_device_id);
22655 __tmp.put_u8(self.primary_control_sysid);
22656 __tmp.put_u8(self.primary_control_compid);
22657 __tmp.put_u8(self.secondary_control_sysid);
22658 __tmp.put_u8(self.secondary_control_compid);
22659 if matches!(version, MavlinkVersion::V2) {
22660 let len = __tmp.len();
22661 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22662 } else {
22663 __tmp.len()
22664 }
22665 }
22666}
22667#[doc = "id: 121"]
22668#[doc = "Erase all logs."]
22669#[derive(Debug, Clone, PartialEq)]
22670#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22671#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22672pub struct LOG_ERASE_DATA {
22673 #[doc = "System ID"]
22674 pub target_system: u8,
22675 #[doc = "Component ID"]
22676 pub target_component: u8,
22677}
22678impl LOG_ERASE_DATA {
22679 pub const ENCODED_LEN: usize = 2usize;
22680 pub const DEFAULT: Self = Self {
22681 target_system: 0_u8,
22682 target_component: 0_u8,
22683 };
22684 #[cfg(feature = "arbitrary")]
22685 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22686 use arbitrary::{Arbitrary, Unstructured};
22687 let mut buf = [0u8; 1024];
22688 rng.fill_bytes(&mut buf);
22689 let mut unstructured = Unstructured::new(&buf);
22690 Self::arbitrary(&mut unstructured).unwrap_or_default()
22691 }
22692}
22693impl Default for LOG_ERASE_DATA {
22694 fn default() -> Self {
22695 Self::DEFAULT.clone()
22696 }
22697}
22698impl MessageData for LOG_ERASE_DATA {
22699 type Message = MavMessage;
22700 const ID: u32 = 121u32;
22701 const NAME: &'static str = "LOG_ERASE";
22702 const EXTRA_CRC: u8 = 237u8;
22703 const ENCODED_LEN: usize = 2usize;
22704 fn deser(
22705 _version: MavlinkVersion,
22706 __input: &[u8],
22707 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22708 let avail_len = __input.len();
22709 let mut payload_buf = [0; Self::ENCODED_LEN];
22710 let mut buf = if avail_len < Self::ENCODED_LEN {
22711 payload_buf[0..avail_len].copy_from_slice(__input);
22712 Bytes::new(&payload_buf)
22713 } else {
22714 Bytes::new(__input)
22715 };
22716 let mut __struct = Self::default();
22717 __struct.target_system = buf.get_u8();
22718 __struct.target_component = buf.get_u8();
22719 Ok(__struct)
22720 }
22721 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22722 let mut __tmp = BytesMut::new(bytes);
22723 #[allow(clippy::absurd_extreme_comparisons)]
22724 #[allow(unused_comparisons)]
22725 if __tmp.remaining() < Self::ENCODED_LEN {
22726 panic!(
22727 "buffer is too small (need {} bytes, but got {})",
22728 Self::ENCODED_LEN,
22729 __tmp.remaining(),
22730 )
22731 }
22732 __tmp.put_u8(self.target_system);
22733 __tmp.put_u8(self.target_component);
22734 if matches!(version, MavlinkVersion::V2) {
22735 let len = __tmp.len();
22736 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22737 } else {
22738 __tmp.len()
22739 }
22740 }
22741}
22742#[doc = "id: 20"]
22743#[doc = "value[float]. This allows to send a parameter to any other component (such as the GCS) without the need of previous knowledge of possible parameter names. Thus the same GCS can store different parameters for different autopilots. See also <https://mavlink.io/en/services/parameter.html> for a full documentation of QGroundControl and IMU code."]
22744#[derive(Debug, Clone, PartialEq)]
22745#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22746#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22747pub struct PARAM_REQUEST_READ_DATA {
22748 #[doc = "Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored)"]
22749 pub param_index: i16,
22750 #[doc = "System ID"]
22751 pub target_system: u8,
22752 #[doc = "Component ID"]
22753 pub target_component: u8,
22754 #[doc = "Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string"]
22755 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
22756 pub param_id: [u8; 16],
22757}
22758impl PARAM_REQUEST_READ_DATA {
22759 pub const ENCODED_LEN: usize = 20usize;
22760 pub const DEFAULT: Self = Self {
22761 param_index: 0_i16,
22762 target_system: 0_u8,
22763 target_component: 0_u8,
22764 param_id: [0_u8; 16usize],
22765 };
22766 #[cfg(feature = "arbitrary")]
22767 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22768 use arbitrary::{Arbitrary, Unstructured};
22769 let mut buf = [0u8; 1024];
22770 rng.fill_bytes(&mut buf);
22771 let mut unstructured = Unstructured::new(&buf);
22772 Self::arbitrary(&mut unstructured).unwrap_or_default()
22773 }
22774}
22775impl Default for PARAM_REQUEST_READ_DATA {
22776 fn default() -> Self {
22777 Self::DEFAULT.clone()
22778 }
22779}
22780impl MessageData for PARAM_REQUEST_READ_DATA {
22781 type Message = MavMessage;
22782 const ID: u32 = 20u32;
22783 const NAME: &'static str = "PARAM_REQUEST_READ";
22784 const EXTRA_CRC: u8 = 214u8;
22785 const ENCODED_LEN: usize = 20usize;
22786 fn deser(
22787 _version: MavlinkVersion,
22788 __input: &[u8],
22789 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22790 let avail_len = __input.len();
22791 let mut payload_buf = [0; Self::ENCODED_LEN];
22792 let mut buf = if avail_len < Self::ENCODED_LEN {
22793 payload_buf[0..avail_len].copy_from_slice(__input);
22794 Bytes::new(&payload_buf)
22795 } else {
22796 Bytes::new(__input)
22797 };
22798 let mut __struct = Self::default();
22799 __struct.param_index = buf.get_i16_le();
22800 __struct.target_system = buf.get_u8();
22801 __struct.target_component = buf.get_u8();
22802 for v in &mut __struct.param_id {
22803 let val = buf.get_u8();
22804 *v = val;
22805 }
22806 Ok(__struct)
22807 }
22808 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22809 let mut __tmp = BytesMut::new(bytes);
22810 #[allow(clippy::absurd_extreme_comparisons)]
22811 #[allow(unused_comparisons)]
22812 if __tmp.remaining() < Self::ENCODED_LEN {
22813 panic!(
22814 "buffer is too small (need {} bytes, but got {})",
22815 Self::ENCODED_LEN,
22816 __tmp.remaining(),
22817 )
22818 }
22819 __tmp.put_i16_le(self.param_index);
22820 __tmp.put_u8(self.target_system);
22821 __tmp.put_u8(self.target_component);
22822 for val in &self.param_id {
22823 __tmp.put_u8(*val);
22824 }
22825 if matches!(version, MavlinkVersion::V2) {
22826 let len = __tmp.len();
22827 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22828 } else {
22829 __tmp.len()
22830 }
22831 }
22832}
22833#[doc = "id: 90"]
22834#[doc = "Sent from simulation to autopilot. This packet is useful for high throughput applications such as hardware in the loop simulations."]
22835#[derive(Debug, Clone, PartialEq)]
22836#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22837#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22838pub struct HIL_STATE_DATA {
22839 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
22840 pub time_usec: u64,
22841 #[doc = "Roll angle"]
22842 pub roll: f32,
22843 #[doc = "Pitch angle"]
22844 pub pitch: f32,
22845 #[doc = "Yaw angle"]
22846 pub yaw: f32,
22847 #[doc = "Body frame roll / phi angular speed"]
22848 pub rollspeed: f32,
22849 #[doc = "Body frame pitch / theta angular speed"]
22850 pub pitchspeed: f32,
22851 #[doc = "Body frame yaw / psi angular speed"]
22852 pub yawspeed: f32,
22853 #[doc = "Latitude"]
22854 pub lat: i32,
22855 #[doc = "Longitude"]
22856 pub lon: i32,
22857 #[doc = "Altitude"]
22858 pub alt: i32,
22859 #[doc = "Ground X Speed (Latitude)"]
22860 pub vx: i16,
22861 #[doc = "Ground Y Speed (Longitude)"]
22862 pub vy: i16,
22863 #[doc = "Ground Z Speed (Altitude)"]
22864 pub vz: i16,
22865 #[doc = "X acceleration"]
22866 pub xacc: i16,
22867 #[doc = "Y acceleration"]
22868 pub yacc: i16,
22869 #[doc = "Z acceleration"]
22870 pub zacc: i16,
22871}
22872impl HIL_STATE_DATA {
22873 pub const ENCODED_LEN: usize = 56usize;
22874 pub const DEFAULT: Self = Self {
22875 time_usec: 0_u64,
22876 roll: 0.0_f32,
22877 pitch: 0.0_f32,
22878 yaw: 0.0_f32,
22879 rollspeed: 0.0_f32,
22880 pitchspeed: 0.0_f32,
22881 yawspeed: 0.0_f32,
22882 lat: 0_i32,
22883 lon: 0_i32,
22884 alt: 0_i32,
22885 vx: 0_i16,
22886 vy: 0_i16,
22887 vz: 0_i16,
22888 xacc: 0_i16,
22889 yacc: 0_i16,
22890 zacc: 0_i16,
22891 };
22892 #[cfg(feature = "arbitrary")]
22893 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22894 use arbitrary::{Arbitrary, Unstructured};
22895 let mut buf = [0u8; 1024];
22896 rng.fill_bytes(&mut buf);
22897 let mut unstructured = Unstructured::new(&buf);
22898 Self::arbitrary(&mut unstructured).unwrap_or_default()
22899 }
22900}
22901impl Default for HIL_STATE_DATA {
22902 fn default() -> Self {
22903 Self::DEFAULT.clone()
22904 }
22905}
22906impl MessageData for HIL_STATE_DATA {
22907 type Message = MavMessage;
22908 const ID: u32 = 90u32;
22909 const NAME: &'static str = "HIL_STATE";
22910 const EXTRA_CRC: u8 = 183u8;
22911 const ENCODED_LEN: usize = 56usize;
22912 fn deser(
22913 _version: MavlinkVersion,
22914 __input: &[u8],
22915 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22916 let avail_len = __input.len();
22917 let mut payload_buf = [0; Self::ENCODED_LEN];
22918 let mut buf = if avail_len < Self::ENCODED_LEN {
22919 payload_buf[0..avail_len].copy_from_slice(__input);
22920 Bytes::new(&payload_buf)
22921 } else {
22922 Bytes::new(__input)
22923 };
22924 let mut __struct = Self::default();
22925 __struct.time_usec = buf.get_u64_le();
22926 __struct.roll = buf.get_f32_le();
22927 __struct.pitch = buf.get_f32_le();
22928 __struct.yaw = buf.get_f32_le();
22929 __struct.rollspeed = buf.get_f32_le();
22930 __struct.pitchspeed = buf.get_f32_le();
22931 __struct.yawspeed = buf.get_f32_le();
22932 __struct.lat = buf.get_i32_le();
22933 __struct.lon = buf.get_i32_le();
22934 __struct.alt = buf.get_i32_le();
22935 __struct.vx = buf.get_i16_le();
22936 __struct.vy = buf.get_i16_le();
22937 __struct.vz = buf.get_i16_le();
22938 __struct.xacc = buf.get_i16_le();
22939 __struct.yacc = buf.get_i16_le();
22940 __struct.zacc = buf.get_i16_le();
22941 Ok(__struct)
22942 }
22943 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22944 let mut __tmp = BytesMut::new(bytes);
22945 #[allow(clippy::absurd_extreme_comparisons)]
22946 #[allow(unused_comparisons)]
22947 if __tmp.remaining() < Self::ENCODED_LEN {
22948 panic!(
22949 "buffer is too small (need {} bytes, but got {})",
22950 Self::ENCODED_LEN,
22951 __tmp.remaining(),
22952 )
22953 }
22954 __tmp.put_u64_le(self.time_usec);
22955 __tmp.put_f32_le(self.roll);
22956 __tmp.put_f32_le(self.pitch);
22957 __tmp.put_f32_le(self.yaw);
22958 __tmp.put_f32_le(self.rollspeed);
22959 __tmp.put_f32_le(self.pitchspeed);
22960 __tmp.put_f32_le(self.yawspeed);
22961 __tmp.put_i32_le(self.lat);
22962 __tmp.put_i32_le(self.lon);
22963 __tmp.put_i32_le(self.alt);
22964 __tmp.put_i16_le(self.vx);
22965 __tmp.put_i16_le(self.vy);
22966 __tmp.put_i16_le(self.vz);
22967 __tmp.put_i16_le(self.xacc);
22968 __tmp.put_i16_le(self.yacc);
22969 __tmp.put_i16_le(self.zacc);
22970 if matches!(version, MavlinkVersion::V2) {
22971 let len = __tmp.len();
22972 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22973 } else {
22974 __tmp.len()
22975 }
22976 }
22977}
22978#[doc = "id: 411"]
22979#[doc = "Regular broadcast for the current latest event sequence number for a component. This is used to check for dropped events."]
22980#[derive(Debug, Clone, PartialEq)]
22981#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22982#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22983pub struct CURRENT_EVENT_SEQUENCE_DATA {
22984 #[doc = "Sequence number."]
22985 pub sequence: u16,
22986 #[doc = "Flag bitset."]
22987 pub flags: MavEventCurrentSequenceFlags,
22988}
22989impl CURRENT_EVENT_SEQUENCE_DATA {
22990 pub const ENCODED_LEN: usize = 3usize;
22991 pub const DEFAULT: Self = Self {
22992 sequence: 0_u16,
22993 flags: MavEventCurrentSequenceFlags::DEFAULT,
22994 };
22995 #[cfg(feature = "arbitrary")]
22996 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22997 use arbitrary::{Arbitrary, Unstructured};
22998 let mut buf = [0u8; 1024];
22999 rng.fill_bytes(&mut buf);
23000 let mut unstructured = Unstructured::new(&buf);
23001 Self::arbitrary(&mut unstructured).unwrap_or_default()
23002 }
23003}
23004impl Default for CURRENT_EVENT_SEQUENCE_DATA {
23005 fn default() -> Self {
23006 Self::DEFAULT.clone()
23007 }
23008}
23009impl MessageData for CURRENT_EVENT_SEQUENCE_DATA {
23010 type Message = MavMessage;
23011 const ID: u32 = 411u32;
23012 const NAME: &'static str = "CURRENT_EVENT_SEQUENCE";
23013 const EXTRA_CRC: u8 = 106u8;
23014 const ENCODED_LEN: usize = 3usize;
23015 fn deser(
23016 _version: MavlinkVersion,
23017 __input: &[u8],
23018 ) -> Result<Self, ::mavlink_core::error::ParserError> {
23019 let avail_len = __input.len();
23020 let mut payload_buf = [0; Self::ENCODED_LEN];
23021 let mut buf = if avail_len < Self::ENCODED_LEN {
23022 payload_buf[0..avail_len].copy_from_slice(__input);
23023 Bytes::new(&payload_buf)
23024 } else {
23025 Bytes::new(__input)
23026 };
23027 let mut __struct = Self::default();
23028 __struct.sequence = buf.get_u16_le();
23029 let tmp = buf.get_u8();
23030 __struct.flags =
23031 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23032 enum_type: "MavEventCurrentSequenceFlags",
23033 value: tmp as u32,
23034 })?;
23035 Ok(__struct)
23036 }
23037 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
23038 let mut __tmp = BytesMut::new(bytes);
23039 #[allow(clippy::absurd_extreme_comparisons)]
23040 #[allow(unused_comparisons)]
23041 if __tmp.remaining() < Self::ENCODED_LEN {
23042 panic!(
23043 "buffer is too small (need {} bytes, but got {})",
23044 Self::ENCODED_LEN,
23045 __tmp.remaining(),
23046 )
23047 }
23048 __tmp.put_u16_le(self.sequence);
23049 __tmp.put_u8(self.flags as u8);
23050 if matches!(version, MavlinkVersion::V2) {
23051 let len = __tmp.len();
23052 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
23053 } else {
23054 __tmp.len()
23055 }
23056 }
23057}
23058#[doc = "id: 118"]
23059#[doc = "Reply to LOG_REQUEST_LIST."]
23060#[derive(Debug, Clone, PartialEq)]
23061#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
23062#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
23063pub struct LOG_ENTRY_DATA {
23064 #[doc = "UTC timestamp of log since 1970, or 0 if not available"]
23065 pub time_utc: u32,
23066 #[doc = "Size of the log (may be approximate)"]
23067 pub size: u32,
23068 #[doc = "Log id"]
23069 pub id: u16,
23070 #[doc = "Total number of logs"]
23071 pub num_logs: u16,
23072 #[doc = "High log number"]
23073 pub last_log_num: u16,
23074}
23075impl LOG_ENTRY_DATA {
23076 pub const ENCODED_LEN: usize = 14usize;
23077 pub const DEFAULT: Self = Self {
23078 time_utc: 0_u32,
23079 size: 0_u32,
23080 id: 0_u16,
23081 num_logs: 0_u16,
23082 last_log_num: 0_u16,
23083 };
23084 #[cfg(feature = "arbitrary")]
23085 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
23086 use arbitrary::{Arbitrary, Unstructured};
23087 let mut buf = [0u8; 1024];
23088 rng.fill_bytes(&mut buf);
23089 let mut unstructured = Unstructured::new(&buf);
23090 Self::arbitrary(&mut unstructured).unwrap_or_default()
23091 }
23092}
23093impl Default for LOG_ENTRY_DATA {
23094 fn default() -> Self {
23095 Self::DEFAULT.clone()
23096 }
23097}
23098impl MessageData for LOG_ENTRY_DATA {
23099 type Message = MavMessage;
23100 const ID: u32 = 118u32;
23101 const NAME: &'static str = "LOG_ENTRY";
23102 const EXTRA_CRC: u8 = 56u8;
23103 const ENCODED_LEN: usize = 14usize;
23104 fn deser(
23105 _version: MavlinkVersion,
23106 __input: &[u8],
23107 ) -> Result<Self, ::mavlink_core::error::ParserError> {
23108 let avail_len = __input.len();
23109 let mut payload_buf = [0; Self::ENCODED_LEN];
23110 let mut buf = if avail_len < Self::ENCODED_LEN {
23111 payload_buf[0..avail_len].copy_from_slice(__input);
23112 Bytes::new(&payload_buf)
23113 } else {
23114 Bytes::new(__input)
23115 };
23116 let mut __struct = Self::default();
23117 __struct.time_utc = buf.get_u32_le();
23118 __struct.size = buf.get_u32_le();
23119 __struct.id = buf.get_u16_le();
23120 __struct.num_logs = buf.get_u16_le();
23121 __struct.last_log_num = buf.get_u16_le();
23122 Ok(__struct)
23123 }
23124 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
23125 let mut __tmp = BytesMut::new(bytes);
23126 #[allow(clippy::absurd_extreme_comparisons)]
23127 #[allow(unused_comparisons)]
23128 if __tmp.remaining() < Self::ENCODED_LEN {
23129 panic!(
23130 "buffer is too small (need {} bytes, but got {})",
23131 Self::ENCODED_LEN,
23132 __tmp.remaining(),
23133 )
23134 }
23135 __tmp.put_u32_le(self.time_utc);
23136 __tmp.put_u32_le(self.size);
23137 __tmp.put_u16_le(self.id);
23138 __tmp.put_u16_le(self.num_logs);
23139 __tmp.put_u16_le(self.last_log_num);
23140 if matches!(version, MavlinkVersion::V2) {
23141 let len = __tmp.len();
23142 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
23143 } else {
23144 __tmp.len()
23145 }
23146 }
23147}
23148#[doc = "id: 73"]
23149#[doc = "Message encoding a mission item. This message is emitted to announce the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). NaN or INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component's current latitude, yaw rather than a specific value). See also <https://mavlink.io/en/services/mission.html>."]
23150#[derive(Debug, Clone, PartialEq)]
23151#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
23152#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
23153pub struct MISSION_ITEM_INT_DATA {
23154 #[doc = "PARAM1, see MAV_CMD enum"]
23155 pub param1: f32,
23156 #[doc = "PARAM2, see MAV_CMD enum"]
23157 pub param2: f32,
23158 #[doc = "PARAM3, see MAV_CMD enum"]
23159 pub param3: f32,
23160 #[doc = "PARAM4, see MAV_CMD enum"]
23161 pub param4: f32,
23162 #[doc = "PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7"]
23163 pub x: i32,
23164 #[doc = "PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7"]
23165 pub y: i32,
23166 #[doc = "PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame."]
23167 pub z: f32,
23168 #[doc = "Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4)."]
23169 pub seq: u16,
23170 #[doc = "The scheduled action for the waypoint."]
23171 pub command: MavCmd,
23172 #[doc = "System ID"]
23173 pub target_system: u8,
23174 #[doc = "Component ID"]
23175 pub target_component: u8,
23176 #[doc = "The coordinate system of the waypoint."]
23177 pub frame: MavFrame,
23178 #[doc = "false:0, true:1"]
23179 pub current: u8,
23180 #[doc = "Autocontinue to next waypoint. 0: false, 1: true. Set false to pause mission after the item completes."]
23181 pub autocontinue: u8,
23182 #[doc = "Mission type."]
23183 #[cfg_attr(feature = "serde", serde(default))]
23184 pub mission_type: MavMissionType,
23185}
23186impl MISSION_ITEM_INT_DATA {
23187 pub const ENCODED_LEN: usize = 38usize;
23188 pub const DEFAULT: Self = Self {
23189 param1: 0.0_f32,
23190 param2: 0.0_f32,
23191 param3: 0.0_f32,
23192 param4: 0.0_f32,
23193 x: 0_i32,
23194 y: 0_i32,
23195 z: 0.0_f32,
23196 seq: 0_u16,
23197 command: MavCmd::DEFAULT,
23198 target_system: 0_u8,
23199 target_component: 0_u8,
23200 frame: MavFrame::DEFAULT,
23201 current: 0_u8,
23202 autocontinue: 0_u8,
23203 mission_type: MavMissionType::DEFAULT,
23204 };
23205 #[cfg(feature = "arbitrary")]
23206 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
23207 use arbitrary::{Arbitrary, Unstructured};
23208 let mut buf = [0u8; 1024];
23209 rng.fill_bytes(&mut buf);
23210 let mut unstructured = Unstructured::new(&buf);
23211 Self::arbitrary(&mut unstructured).unwrap_or_default()
23212 }
23213}
23214impl Default for MISSION_ITEM_INT_DATA {
23215 fn default() -> Self {
23216 Self::DEFAULT.clone()
23217 }
23218}
23219impl MessageData for MISSION_ITEM_INT_DATA {
23220 type Message = MavMessage;
23221 const ID: u32 = 73u32;
23222 const NAME: &'static str = "MISSION_ITEM_INT";
23223 const EXTRA_CRC: u8 = 38u8;
23224 const ENCODED_LEN: usize = 38usize;
23225 fn deser(
23226 _version: MavlinkVersion,
23227 __input: &[u8],
23228 ) -> Result<Self, ::mavlink_core::error::ParserError> {
23229 let avail_len = __input.len();
23230 let mut payload_buf = [0; Self::ENCODED_LEN];
23231 let mut buf = if avail_len < Self::ENCODED_LEN {
23232 payload_buf[0..avail_len].copy_from_slice(__input);
23233 Bytes::new(&payload_buf)
23234 } else {
23235 Bytes::new(__input)
23236 };
23237 let mut __struct = Self::default();
23238 __struct.param1 = buf.get_f32_le();
23239 __struct.param2 = buf.get_f32_le();
23240 __struct.param3 = buf.get_f32_le();
23241 __struct.param4 = buf.get_f32_le();
23242 __struct.x = buf.get_i32_le();
23243 __struct.y = buf.get_i32_le();
23244 __struct.z = buf.get_f32_le();
23245 __struct.seq = buf.get_u16_le();
23246 let tmp = buf.get_u16_le();
23247 __struct.command = FromPrimitive::from_u16(tmp).ok_or(
23248 ::mavlink_core::error::ParserError::InvalidEnum {
23249 enum_type: "MavCmd",
23250 value: tmp as u32,
23251 },
23252 )?;
23253 __struct.target_system = buf.get_u8();
23254 __struct.target_component = buf.get_u8();
23255 let tmp = buf.get_u8();
23256 __struct.frame =
23257 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23258 enum_type: "MavFrame",
23259 value: tmp as u32,
23260 })?;
23261 __struct.current = buf.get_u8();
23262 __struct.autocontinue = buf.get_u8();
23263 let tmp = buf.get_u8();
23264 __struct.mission_type =
23265 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23266 enum_type: "MavMissionType",
23267 value: tmp as u32,
23268 })?;
23269 Ok(__struct)
23270 }
23271 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
23272 let mut __tmp = BytesMut::new(bytes);
23273 #[allow(clippy::absurd_extreme_comparisons)]
23274 #[allow(unused_comparisons)]
23275 if __tmp.remaining() < Self::ENCODED_LEN {
23276 panic!(
23277 "buffer is too small (need {} bytes, but got {})",
23278 Self::ENCODED_LEN,
23279 __tmp.remaining(),
23280 )
23281 }
23282 __tmp.put_f32_le(self.param1);
23283 __tmp.put_f32_le(self.param2);
23284 __tmp.put_f32_le(self.param3);
23285 __tmp.put_f32_le(self.param4);
23286 __tmp.put_i32_le(self.x);
23287 __tmp.put_i32_le(self.y);
23288 __tmp.put_f32_le(self.z);
23289 __tmp.put_u16_le(self.seq);
23290 __tmp.put_u16_le(self.command as u16);
23291 __tmp.put_u8(self.target_system);
23292 __tmp.put_u8(self.target_component);
23293 __tmp.put_u8(self.frame as u8);
23294 __tmp.put_u8(self.current);
23295 __tmp.put_u8(self.autocontinue);
23296 __tmp.put_u8(self.mission_type as u8);
23297 if matches!(version, MavlinkVersion::V2) {
23298 let len = __tmp.len();
23299 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
23300 } else {
23301 __tmp.len()
23302 }
23303 }
23304}
23305#[doc = "id: 235"]
23306#[doc = "Message appropriate for high latency connections like Iridium (version 2)."]
23307#[derive(Debug, Clone, PartialEq)]
23308#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
23309#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
23310pub struct HIGH_LATENCY2_DATA {
23311 #[doc = "Timestamp (milliseconds since boot or Unix epoch)"]
23312 pub timestamp: u32,
23313 #[doc = "Latitude"]
23314 pub latitude: i32,
23315 #[doc = "Longitude"]
23316 pub longitude: i32,
23317 #[doc = "A bitfield for use for autopilot-specific flags (2 byte version)."]
23318 pub custom_mode: u16,
23319 #[doc = "Altitude above mean sea level"]
23320 pub altitude: i16,
23321 #[doc = "Altitude setpoint"]
23322 pub target_altitude: i16,
23323 #[doc = "Distance to target waypoint or position"]
23324 pub target_distance: u16,
23325 #[doc = "Current waypoint number"]
23326 pub wp_num: u16,
23327 #[doc = "Bitmap of failure flags."]
23328 pub failure_flags: HlFailureFlag,
23329 #[doc = "Type of the MAV (quadrotor, helicopter, etc.)"]
23330 pub mavtype: MavType,
23331 #[doc = "Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers."]
23332 pub autopilot: MavAutopilot,
23333 #[doc = "Heading"]
23334 pub heading: u8,
23335 #[doc = "Heading setpoint"]
23336 pub target_heading: u8,
23337 #[doc = "Throttle"]
23338 pub throttle: u8,
23339 #[doc = "Airspeed"]
23340 pub airspeed: u8,
23341 #[doc = "Airspeed setpoint"]
23342 pub airspeed_sp: u8,
23343 #[doc = "Groundspeed"]
23344 pub groundspeed: u8,
23345 #[doc = "Windspeed"]
23346 pub windspeed: u8,
23347 #[doc = "Wind heading"]
23348 pub wind_heading: u8,
23349 #[doc = "Maximum error horizontal position since last message"]
23350 pub eph: u8,
23351 #[doc = "Maximum error vertical position since last message"]
23352 pub epv: u8,
23353 #[doc = "Air temperature"]
23354 pub temperature_air: i8,
23355 #[doc = "Maximum climb rate magnitude since last message"]
23356 pub climb_rate: i8,
23357 #[doc = "Battery level (-1 if field not provided)."]
23358 pub battery: i8,
23359 #[doc = "Field for custom payload."]
23360 pub custom0: i8,
23361 #[doc = "Field for custom payload."]
23362 pub custom1: i8,
23363 #[doc = "Field for custom payload."]
23364 pub custom2: i8,
23365}
23366impl HIGH_LATENCY2_DATA {
23367 pub const ENCODED_LEN: usize = 42usize;
23368 pub const DEFAULT: Self = Self {
23369 timestamp: 0_u32,
23370 latitude: 0_i32,
23371 longitude: 0_i32,
23372 custom_mode: 0_u16,
23373 altitude: 0_i16,
23374 target_altitude: 0_i16,
23375 target_distance: 0_u16,
23376 wp_num: 0_u16,
23377 failure_flags: HlFailureFlag::DEFAULT,
23378 mavtype: MavType::DEFAULT,
23379 autopilot: MavAutopilot::DEFAULT,
23380 heading: 0_u8,
23381 target_heading: 0_u8,
23382 throttle: 0_u8,
23383 airspeed: 0_u8,
23384 airspeed_sp: 0_u8,
23385 groundspeed: 0_u8,
23386 windspeed: 0_u8,
23387 wind_heading: 0_u8,
23388 eph: 0_u8,
23389 epv: 0_u8,
23390 temperature_air: 0_i8,
23391 climb_rate: 0_i8,
23392 battery: 0_i8,
23393 custom0: 0_i8,
23394 custom1: 0_i8,
23395 custom2: 0_i8,
23396 };
23397 #[cfg(feature = "arbitrary")]
23398 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
23399 use arbitrary::{Arbitrary, Unstructured};
23400 let mut buf = [0u8; 1024];
23401 rng.fill_bytes(&mut buf);
23402 let mut unstructured = Unstructured::new(&buf);
23403 Self::arbitrary(&mut unstructured).unwrap_or_default()
23404 }
23405}
23406impl Default for HIGH_LATENCY2_DATA {
23407 fn default() -> Self {
23408 Self::DEFAULT.clone()
23409 }
23410}
23411impl MessageData for HIGH_LATENCY2_DATA {
23412 type Message = MavMessage;
23413 const ID: u32 = 235u32;
23414 const NAME: &'static str = "HIGH_LATENCY2";
23415 const EXTRA_CRC: u8 = 179u8;
23416 const ENCODED_LEN: usize = 42usize;
23417 fn deser(
23418 _version: MavlinkVersion,
23419 __input: &[u8],
23420 ) -> Result<Self, ::mavlink_core::error::ParserError> {
23421 let avail_len = __input.len();
23422 let mut payload_buf = [0; Self::ENCODED_LEN];
23423 let mut buf = if avail_len < Self::ENCODED_LEN {
23424 payload_buf[0..avail_len].copy_from_slice(__input);
23425 Bytes::new(&payload_buf)
23426 } else {
23427 Bytes::new(__input)
23428 };
23429 let mut __struct = Self::default();
23430 __struct.timestamp = buf.get_u32_le();
23431 __struct.latitude = buf.get_i32_le();
23432 __struct.longitude = buf.get_i32_le();
23433 __struct.custom_mode = buf.get_u16_le();
23434 __struct.altitude = buf.get_i16_le();
23435 __struct.target_altitude = buf.get_i16_le();
23436 __struct.target_distance = buf.get_u16_le();
23437 __struct.wp_num = buf.get_u16_le();
23438 let tmp = buf.get_u16_le();
23439 __struct.failure_flags = HlFailureFlag::from_bits(tmp & HlFailureFlag::all().bits())
23440 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
23441 flag_type: "HlFailureFlag",
23442 value: tmp as u32,
23443 })?;
23444 let tmp = buf.get_u8();
23445 __struct.mavtype =
23446 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23447 enum_type: "MavType",
23448 value: tmp as u32,
23449 })?;
23450 let tmp = buf.get_u8();
23451 __struct.autopilot =
23452 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23453 enum_type: "MavAutopilot",
23454 value: tmp as u32,
23455 })?;
23456 __struct.heading = buf.get_u8();
23457 __struct.target_heading = buf.get_u8();
23458 __struct.throttle = buf.get_u8();
23459 __struct.airspeed = buf.get_u8();
23460 __struct.airspeed_sp = buf.get_u8();
23461 __struct.groundspeed = buf.get_u8();
23462 __struct.windspeed = buf.get_u8();
23463 __struct.wind_heading = buf.get_u8();
23464 __struct.eph = buf.get_u8();
23465 __struct.epv = buf.get_u8();
23466 __struct.temperature_air = buf.get_i8();
23467 __struct.climb_rate = buf.get_i8();
23468 __struct.battery = buf.get_i8();
23469 __struct.custom0 = buf.get_i8();
23470 __struct.custom1 = buf.get_i8();
23471 __struct.custom2 = buf.get_i8();
23472 Ok(__struct)
23473 }
23474 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
23475 let mut __tmp = BytesMut::new(bytes);
23476 #[allow(clippy::absurd_extreme_comparisons)]
23477 #[allow(unused_comparisons)]
23478 if __tmp.remaining() < Self::ENCODED_LEN {
23479 panic!(
23480 "buffer is too small (need {} bytes, but got {})",
23481 Self::ENCODED_LEN,
23482 __tmp.remaining(),
23483 )
23484 }
23485 __tmp.put_u32_le(self.timestamp);
23486 __tmp.put_i32_le(self.latitude);
23487 __tmp.put_i32_le(self.longitude);
23488 __tmp.put_u16_le(self.custom_mode);
23489 __tmp.put_i16_le(self.altitude);
23490 __tmp.put_i16_le(self.target_altitude);
23491 __tmp.put_u16_le(self.target_distance);
23492 __tmp.put_u16_le(self.wp_num);
23493 __tmp.put_u16_le(self.failure_flags.bits());
23494 __tmp.put_u8(self.mavtype as u8);
23495 __tmp.put_u8(self.autopilot as u8);
23496 __tmp.put_u8(self.heading);
23497 __tmp.put_u8(self.target_heading);
23498 __tmp.put_u8(self.throttle);
23499 __tmp.put_u8(self.airspeed);
23500 __tmp.put_u8(self.airspeed_sp);
23501 __tmp.put_u8(self.groundspeed);
23502 __tmp.put_u8(self.windspeed);
23503 __tmp.put_u8(self.wind_heading);
23504 __tmp.put_u8(self.eph);
23505 __tmp.put_u8(self.epv);
23506 __tmp.put_i8(self.temperature_air);
23507 __tmp.put_i8(self.climb_rate);
23508 __tmp.put_i8(self.battery);
23509 __tmp.put_i8(self.custom0);
23510 __tmp.put_i8(self.custom1);
23511 __tmp.put_i8(self.custom2);
23512 if matches!(version, MavlinkVersion::V2) {
23513 let len = __tmp.len();
23514 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
23515 } else {
23516 __tmp.len()
23517 }
23518 }
23519}
23520#[doc = "id: 334"]
23521#[doc = "Report current used cellular network status."]
23522#[derive(Debug, Clone, PartialEq)]
23523#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
23524#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
23525pub struct CELLULAR_STATUS_DATA {
23526 #[doc = "Mobile country code. If unknown, set to UINT16_MAX"]
23527 pub mcc: u16,
23528 #[doc = "Mobile network code. If unknown, set to UINT16_MAX"]
23529 pub mnc: u16,
23530 #[doc = "Location area code. If unknown, set to 0"]
23531 pub lac: u16,
23532 #[doc = "Cellular modem status"]
23533 pub status: CellularStatusFlag,
23534 #[doc = "Failure reason when status in in CELLULAR_STATUS_FLAG_FAILED"]
23535 pub failure_reason: CellularNetworkFailedReason,
23536 #[doc = "Cellular network radio type: gsm, cdma, lte..."]
23537 pub mavtype: CellularNetworkRadioType,
23538 #[doc = "Signal quality in percent. If unknown, set to UINT8_MAX"]
23539 pub quality: u8,
23540}
23541impl CELLULAR_STATUS_DATA {
23542 pub const ENCODED_LEN: usize = 10usize;
23543 pub const DEFAULT: Self = Self {
23544 mcc: 0_u16,
23545 mnc: 0_u16,
23546 lac: 0_u16,
23547 status: CellularStatusFlag::DEFAULT,
23548 failure_reason: CellularNetworkFailedReason::DEFAULT,
23549 mavtype: CellularNetworkRadioType::DEFAULT,
23550 quality: 0_u8,
23551 };
23552 #[cfg(feature = "arbitrary")]
23553 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
23554 use arbitrary::{Arbitrary, Unstructured};
23555 let mut buf = [0u8; 1024];
23556 rng.fill_bytes(&mut buf);
23557 let mut unstructured = Unstructured::new(&buf);
23558 Self::arbitrary(&mut unstructured).unwrap_or_default()
23559 }
23560}
23561impl Default for CELLULAR_STATUS_DATA {
23562 fn default() -> Self {
23563 Self::DEFAULT.clone()
23564 }
23565}
23566impl MessageData for CELLULAR_STATUS_DATA {
23567 type Message = MavMessage;
23568 const ID: u32 = 334u32;
23569 const NAME: &'static str = "CELLULAR_STATUS";
23570 const EXTRA_CRC: u8 = 72u8;
23571 const ENCODED_LEN: usize = 10usize;
23572 fn deser(
23573 _version: MavlinkVersion,
23574 __input: &[u8],
23575 ) -> Result<Self, ::mavlink_core::error::ParserError> {
23576 let avail_len = __input.len();
23577 let mut payload_buf = [0; Self::ENCODED_LEN];
23578 let mut buf = if avail_len < Self::ENCODED_LEN {
23579 payload_buf[0..avail_len].copy_from_slice(__input);
23580 Bytes::new(&payload_buf)
23581 } else {
23582 Bytes::new(__input)
23583 };
23584 let mut __struct = Self::default();
23585 __struct.mcc = buf.get_u16_le();
23586 __struct.mnc = buf.get_u16_le();
23587 __struct.lac = buf.get_u16_le();
23588 let tmp = buf.get_u8();
23589 __struct.status =
23590 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23591 enum_type: "CellularStatusFlag",
23592 value: tmp as u32,
23593 })?;
23594 let tmp = buf.get_u8();
23595 __struct.failure_reason =
23596 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23597 enum_type: "CellularNetworkFailedReason",
23598 value: tmp as u32,
23599 })?;
23600 let tmp = buf.get_u8();
23601 __struct.mavtype =
23602 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23603 enum_type: "CellularNetworkRadioType",
23604 value: tmp as u32,
23605 })?;
23606 __struct.quality = buf.get_u8();
23607 Ok(__struct)
23608 }
23609 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
23610 let mut __tmp = BytesMut::new(bytes);
23611 #[allow(clippy::absurd_extreme_comparisons)]
23612 #[allow(unused_comparisons)]
23613 if __tmp.remaining() < Self::ENCODED_LEN {
23614 panic!(
23615 "buffer is too small (need {} bytes, but got {})",
23616 Self::ENCODED_LEN,
23617 __tmp.remaining(),
23618 )
23619 }
23620 __tmp.put_u16_le(self.mcc);
23621 __tmp.put_u16_le(self.mnc);
23622 __tmp.put_u16_le(self.lac);
23623 __tmp.put_u8(self.status as u8);
23624 __tmp.put_u8(self.failure_reason as u8);
23625 __tmp.put_u8(self.mavtype as u8);
23626 __tmp.put_u8(self.quality);
23627 if matches!(version, MavlinkVersion::V2) {
23628 let len = __tmp.len();
23629 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
23630 } else {
23631 __tmp.len()
23632 }
23633 }
23634}
23635#[doc = "id: 39"]
23636#[doc = "Message encoding a mission item. This message is emitted to announce the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). NaN may be used to indicate an optional/default value (e.g. to use the system's current latitude or yaw rather than a specific value). See also <https://mavlink.io/en/services/mission.html>."]
23637#[derive(Debug, Clone, PartialEq)]
23638#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
23639#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
23640pub struct MISSION_ITEM_DATA {
23641 #[doc = "PARAM1, see MAV_CMD enum"]
23642 pub param1: f32,
23643 #[doc = "PARAM2, see MAV_CMD enum"]
23644 pub param2: f32,
23645 #[doc = "PARAM3, see MAV_CMD enum"]
23646 pub param3: f32,
23647 #[doc = "PARAM4, see MAV_CMD enum"]
23648 pub param4: f32,
23649 #[doc = "PARAM5 / local: X coordinate, global: latitude"]
23650 pub x: f32,
23651 #[doc = "PARAM6 / local: Y coordinate, global: longitude"]
23652 pub y: f32,
23653 #[doc = "PARAM7 / local: Z coordinate, global: altitude (relative or absolute, depending on frame)."]
23654 pub z: f32,
23655 #[doc = "Sequence"]
23656 pub seq: u16,
23657 #[doc = "The scheduled action for the waypoint."]
23658 pub command: MavCmd,
23659 #[doc = "System ID"]
23660 pub target_system: u8,
23661 #[doc = "Component ID"]
23662 pub target_component: u8,
23663 #[doc = "The coordinate system of the waypoint."]
23664 pub frame: MavFrame,
23665 #[doc = "false:0, true:1"]
23666 pub current: u8,
23667 #[doc = "Autocontinue to next waypoint. 0: false, 1: true. Set false to pause mission after the item completes."]
23668 pub autocontinue: u8,
23669 #[doc = "Mission type."]
23670 #[cfg_attr(feature = "serde", serde(default))]
23671 pub mission_type: MavMissionType,
23672}
23673impl MISSION_ITEM_DATA {
23674 pub const ENCODED_LEN: usize = 38usize;
23675 pub const DEFAULT: Self = Self {
23676 param1: 0.0_f32,
23677 param2: 0.0_f32,
23678 param3: 0.0_f32,
23679 param4: 0.0_f32,
23680 x: 0.0_f32,
23681 y: 0.0_f32,
23682 z: 0.0_f32,
23683 seq: 0_u16,
23684 command: MavCmd::DEFAULT,
23685 target_system: 0_u8,
23686 target_component: 0_u8,
23687 frame: MavFrame::DEFAULT,
23688 current: 0_u8,
23689 autocontinue: 0_u8,
23690 mission_type: MavMissionType::DEFAULT,
23691 };
23692 #[cfg(feature = "arbitrary")]
23693 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
23694 use arbitrary::{Arbitrary, Unstructured};
23695 let mut buf = [0u8; 1024];
23696 rng.fill_bytes(&mut buf);
23697 let mut unstructured = Unstructured::new(&buf);
23698 Self::arbitrary(&mut unstructured).unwrap_or_default()
23699 }
23700}
23701impl Default for MISSION_ITEM_DATA {
23702 fn default() -> Self {
23703 Self::DEFAULT.clone()
23704 }
23705}
23706impl MessageData for MISSION_ITEM_DATA {
23707 type Message = MavMessage;
23708 const ID: u32 = 39u32;
23709 const NAME: &'static str = "MISSION_ITEM";
23710 const EXTRA_CRC: u8 = 254u8;
23711 const ENCODED_LEN: usize = 38usize;
23712 fn deser(
23713 _version: MavlinkVersion,
23714 __input: &[u8],
23715 ) -> Result<Self, ::mavlink_core::error::ParserError> {
23716 let avail_len = __input.len();
23717 let mut payload_buf = [0; Self::ENCODED_LEN];
23718 let mut buf = if avail_len < Self::ENCODED_LEN {
23719 payload_buf[0..avail_len].copy_from_slice(__input);
23720 Bytes::new(&payload_buf)
23721 } else {
23722 Bytes::new(__input)
23723 };
23724 let mut __struct = Self::default();
23725 __struct.param1 = buf.get_f32_le();
23726 __struct.param2 = buf.get_f32_le();
23727 __struct.param3 = buf.get_f32_le();
23728 __struct.param4 = buf.get_f32_le();
23729 __struct.x = buf.get_f32_le();
23730 __struct.y = buf.get_f32_le();
23731 __struct.z = buf.get_f32_le();
23732 __struct.seq = buf.get_u16_le();
23733 let tmp = buf.get_u16_le();
23734 __struct.command = FromPrimitive::from_u16(tmp).ok_or(
23735 ::mavlink_core::error::ParserError::InvalidEnum {
23736 enum_type: "MavCmd",
23737 value: tmp as u32,
23738 },
23739 )?;
23740 __struct.target_system = buf.get_u8();
23741 __struct.target_component = buf.get_u8();
23742 let tmp = buf.get_u8();
23743 __struct.frame =
23744 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23745 enum_type: "MavFrame",
23746 value: tmp as u32,
23747 })?;
23748 __struct.current = buf.get_u8();
23749 __struct.autocontinue = buf.get_u8();
23750 let tmp = buf.get_u8();
23751 __struct.mission_type =
23752 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23753 enum_type: "MavMissionType",
23754 value: tmp as u32,
23755 })?;
23756 Ok(__struct)
23757 }
23758 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
23759 let mut __tmp = BytesMut::new(bytes);
23760 #[allow(clippy::absurd_extreme_comparisons)]
23761 #[allow(unused_comparisons)]
23762 if __tmp.remaining() < Self::ENCODED_LEN {
23763 panic!(
23764 "buffer is too small (need {} bytes, but got {})",
23765 Self::ENCODED_LEN,
23766 __tmp.remaining(),
23767 )
23768 }
23769 __tmp.put_f32_le(self.param1);
23770 __tmp.put_f32_le(self.param2);
23771 __tmp.put_f32_le(self.param3);
23772 __tmp.put_f32_le(self.param4);
23773 __tmp.put_f32_le(self.x);
23774 __tmp.put_f32_le(self.y);
23775 __tmp.put_f32_le(self.z);
23776 __tmp.put_u16_le(self.seq);
23777 __tmp.put_u16_le(self.command as u16);
23778 __tmp.put_u8(self.target_system);
23779 __tmp.put_u8(self.target_component);
23780 __tmp.put_u8(self.frame as u8);
23781 __tmp.put_u8(self.current);
23782 __tmp.put_u8(self.autocontinue);
23783 __tmp.put_u8(self.mission_type as u8);
23784 if matches!(version, MavlinkVersion::V2) {
23785 let len = __tmp.len();
23786 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
23787 } else {
23788 __tmp.len()
23789 }
23790 }
23791}
23792#[doc = "id: 62"]
23793#[doc = "The state of the navigation and position controller."]
23794#[derive(Debug, Clone, PartialEq)]
23795#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
23796#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
23797pub struct NAV_CONTROLLER_OUTPUT_DATA {
23798 #[doc = "Current desired roll"]
23799 pub nav_roll: f32,
23800 #[doc = "Current desired pitch"]
23801 pub nav_pitch: f32,
23802 #[doc = "Current altitude error"]
23803 pub alt_error: f32,
23804 #[doc = "Current airspeed error"]
23805 pub aspd_error: f32,
23806 #[doc = "Current crosstrack error on x-y plane"]
23807 pub xtrack_error: f32,
23808 #[doc = "Current desired heading"]
23809 pub nav_bearing: i16,
23810 #[doc = "Bearing to current waypoint/target"]
23811 pub target_bearing: i16,
23812 #[doc = "Distance to active waypoint"]
23813 pub wp_dist: u16,
23814}
23815impl NAV_CONTROLLER_OUTPUT_DATA {
23816 pub const ENCODED_LEN: usize = 26usize;
23817 pub const DEFAULT: Self = Self {
23818 nav_roll: 0.0_f32,
23819 nav_pitch: 0.0_f32,
23820 alt_error: 0.0_f32,
23821 aspd_error: 0.0_f32,
23822 xtrack_error: 0.0_f32,
23823 nav_bearing: 0_i16,
23824 target_bearing: 0_i16,
23825 wp_dist: 0_u16,
23826 };
23827 #[cfg(feature = "arbitrary")]
23828 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
23829 use arbitrary::{Arbitrary, Unstructured};
23830 let mut buf = [0u8; 1024];
23831 rng.fill_bytes(&mut buf);
23832 let mut unstructured = Unstructured::new(&buf);
23833 Self::arbitrary(&mut unstructured).unwrap_or_default()
23834 }
23835}
23836impl Default for NAV_CONTROLLER_OUTPUT_DATA {
23837 fn default() -> Self {
23838 Self::DEFAULT.clone()
23839 }
23840}
23841impl MessageData for NAV_CONTROLLER_OUTPUT_DATA {
23842 type Message = MavMessage;
23843 const ID: u32 = 62u32;
23844 const NAME: &'static str = "NAV_CONTROLLER_OUTPUT";
23845 const EXTRA_CRC: u8 = 183u8;
23846 const ENCODED_LEN: usize = 26usize;
23847 fn deser(
23848 _version: MavlinkVersion,
23849 __input: &[u8],
23850 ) -> Result<Self, ::mavlink_core::error::ParserError> {
23851 let avail_len = __input.len();
23852 let mut payload_buf = [0; Self::ENCODED_LEN];
23853 let mut buf = if avail_len < Self::ENCODED_LEN {
23854 payload_buf[0..avail_len].copy_from_slice(__input);
23855 Bytes::new(&payload_buf)
23856 } else {
23857 Bytes::new(__input)
23858 };
23859 let mut __struct = Self::default();
23860 __struct.nav_roll = buf.get_f32_le();
23861 __struct.nav_pitch = buf.get_f32_le();
23862 __struct.alt_error = buf.get_f32_le();
23863 __struct.aspd_error = buf.get_f32_le();
23864 __struct.xtrack_error = buf.get_f32_le();
23865 __struct.nav_bearing = buf.get_i16_le();
23866 __struct.target_bearing = buf.get_i16_le();
23867 __struct.wp_dist = buf.get_u16_le();
23868 Ok(__struct)
23869 }
23870 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
23871 let mut __tmp = BytesMut::new(bytes);
23872 #[allow(clippy::absurd_extreme_comparisons)]
23873 #[allow(unused_comparisons)]
23874 if __tmp.remaining() < Self::ENCODED_LEN {
23875 panic!(
23876 "buffer is too small (need {} bytes, but got {})",
23877 Self::ENCODED_LEN,
23878 __tmp.remaining(),
23879 )
23880 }
23881 __tmp.put_f32_le(self.nav_roll);
23882 __tmp.put_f32_le(self.nav_pitch);
23883 __tmp.put_f32_le(self.alt_error);
23884 __tmp.put_f32_le(self.aspd_error);
23885 __tmp.put_f32_le(self.xtrack_error);
23886 __tmp.put_i16_le(self.nav_bearing);
23887 __tmp.put_i16_le(self.target_bearing);
23888 __tmp.put_u16_le(self.wp_dist);
23889 if matches!(version, MavlinkVersion::V2) {
23890 let len = __tmp.len();
23891 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
23892 } else {
23893 __tmp.len()
23894 }
23895 }
23896}
23897#[doc = "id: 285"]
23898#[doc = "Message reporting the status of a gimbal device. \t This message should be broadcast by a gimbal device component at a low regular rate (e.g. 5 Hz). \t For the angles encoded in the quaternion and the angular velocities holds: \t If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME is set, then they are relative to the vehicle heading (vehicle frame). \t If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is set, then they are relative to absolute North (earth frame). \t If neither of these flags are set, then (for backwards compatibility) it holds: \t If the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, then they are relative to absolute North (earth frame), \t else they are relative to the vehicle heading (vehicle frame). \t Other conditions of the flags are not allowed. \t The quaternion and angular velocities in the other frame can be calculated from delta_yaw and delta_yaw_velocity as \t q_earth = q_delta_yaw * q_vehicle and w_earth = w_delta_yaw_velocity + w_vehicle (if not NaN). \t If neither the GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME nor the GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME flag is set, \t then (for backwards compatibility) the data in the delta_yaw and delta_yaw_velocity fields are to be ignored. \t New implementations should always set either GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME or GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME, \t and always should set delta_yaw and delta_yaw_velocity either to the proper value or NaN."]
23899#[derive(Debug, Clone, PartialEq)]
23900#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
23901#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
23902pub struct GIMBAL_DEVICE_ATTITUDE_STATUS_DATA {
23903 #[doc = "Timestamp (time since system boot)."]
23904 pub time_boot_ms: u32,
23905 #[doc = "Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). The frame is described in the message description."]
23906 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23907 pub q: [f32; 4],
23908 #[doc = "X component of angular velocity (positive: rolling to the right). The frame is described in the message description. NaN if unknown."]
23909 pub angular_velocity_x: f32,
23910 #[doc = "Y component of angular velocity (positive: pitching up). The frame is described in the message description. NaN if unknown."]
23911 pub angular_velocity_y: f32,
23912 #[doc = "Z component of angular velocity (positive: yawing to the right). The frame is described in the message description. NaN if unknown."]
23913 pub angular_velocity_z: f32,
23914 #[doc = "Failure flags (0 for no failure)"]
23915 pub failure_flags: GimbalDeviceErrorFlags,
23916 #[doc = "Current gimbal flags set."]
23917 pub flags: GimbalDeviceFlags,
23918 #[doc = "System ID"]
23919 pub target_system: u8,
23920 #[doc = "Component ID"]
23921 pub target_component: u8,
23922 #[doc = "Yaw angle relating the quaternions in earth and body frames (see message description). NaN if unknown."]
23923 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
23924 pub delta_yaw: f32,
23925 #[doc = "Yaw angular velocity relating the angular velocities in earth and body frames (see message description). NaN if unknown."]
23926 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
23927 pub delta_yaw_velocity: f32,
23928 #[doc = "This field is to be used if the gimbal manager and the gimbal device are the same component and hence have the same component ID. This field is then set a number between 1-6. If the component ID is separate, this field is not required and must be set to 0."]
23929 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
23930 pub gimbal_device_id: u8,
23931}
23932impl GIMBAL_DEVICE_ATTITUDE_STATUS_DATA {
23933 pub const ENCODED_LEN: usize = 49usize;
23934 pub const DEFAULT: Self = Self {
23935 time_boot_ms: 0_u32,
23936 q: [0.0_f32; 4usize],
23937 angular_velocity_x: 0.0_f32,
23938 angular_velocity_y: 0.0_f32,
23939 angular_velocity_z: 0.0_f32,
23940 failure_flags: GimbalDeviceErrorFlags::DEFAULT,
23941 flags: GimbalDeviceFlags::DEFAULT,
23942 target_system: 0_u8,
23943 target_component: 0_u8,
23944 delta_yaw: 0.0_f32,
23945 delta_yaw_velocity: 0.0_f32,
23946 gimbal_device_id: 0_u8,
23947 };
23948 #[cfg(feature = "arbitrary")]
23949 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
23950 use arbitrary::{Arbitrary, Unstructured};
23951 let mut buf = [0u8; 1024];
23952 rng.fill_bytes(&mut buf);
23953 let mut unstructured = Unstructured::new(&buf);
23954 Self::arbitrary(&mut unstructured).unwrap_or_default()
23955 }
23956}
23957impl Default for GIMBAL_DEVICE_ATTITUDE_STATUS_DATA {
23958 fn default() -> Self {
23959 Self::DEFAULT.clone()
23960 }
23961}
23962impl MessageData for GIMBAL_DEVICE_ATTITUDE_STATUS_DATA {
23963 type Message = MavMessage;
23964 const ID: u32 = 285u32;
23965 const NAME: &'static str = "GIMBAL_DEVICE_ATTITUDE_STATUS";
23966 const EXTRA_CRC: u8 = 137u8;
23967 const ENCODED_LEN: usize = 49usize;
23968 fn deser(
23969 _version: MavlinkVersion,
23970 __input: &[u8],
23971 ) -> Result<Self, ::mavlink_core::error::ParserError> {
23972 let avail_len = __input.len();
23973 let mut payload_buf = [0; Self::ENCODED_LEN];
23974 let mut buf = if avail_len < Self::ENCODED_LEN {
23975 payload_buf[0..avail_len].copy_from_slice(__input);
23976 Bytes::new(&payload_buf)
23977 } else {
23978 Bytes::new(__input)
23979 };
23980 let mut __struct = Self::default();
23981 __struct.time_boot_ms = buf.get_u32_le();
23982 for v in &mut __struct.q {
23983 let val = buf.get_f32_le();
23984 *v = val;
23985 }
23986 __struct.angular_velocity_x = buf.get_f32_le();
23987 __struct.angular_velocity_y = buf.get_f32_le();
23988 __struct.angular_velocity_z = buf.get_f32_le();
23989 let tmp = buf.get_u32_le();
23990 __struct.failure_flags = GimbalDeviceErrorFlags::from_bits(
23991 tmp & GimbalDeviceErrorFlags::all().bits(),
23992 )
23993 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
23994 flag_type: "GimbalDeviceErrorFlags",
23995 value: tmp as u32,
23996 })?;
23997 let tmp = buf.get_u16_le();
23998 __struct.flags = GimbalDeviceFlags::from_bits(tmp & GimbalDeviceFlags::all().bits())
23999 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
24000 flag_type: "GimbalDeviceFlags",
24001 value: tmp as u32,
24002 })?;
24003 __struct.target_system = buf.get_u8();
24004 __struct.target_component = buf.get_u8();
24005 __struct.delta_yaw = buf.get_f32_le();
24006 __struct.delta_yaw_velocity = buf.get_f32_le();
24007 __struct.gimbal_device_id = buf.get_u8();
24008 Ok(__struct)
24009 }
24010 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24011 let mut __tmp = BytesMut::new(bytes);
24012 #[allow(clippy::absurd_extreme_comparisons)]
24013 #[allow(unused_comparisons)]
24014 if __tmp.remaining() < Self::ENCODED_LEN {
24015 panic!(
24016 "buffer is too small (need {} bytes, but got {})",
24017 Self::ENCODED_LEN,
24018 __tmp.remaining(),
24019 )
24020 }
24021 __tmp.put_u32_le(self.time_boot_ms);
24022 for val in &self.q {
24023 __tmp.put_f32_le(*val);
24024 }
24025 __tmp.put_f32_le(self.angular_velocity_x);
24026 __tmp.put_f32_le(self.angular_velocity_y);
24027 __tmp.put_f32_le(self.angular_velocity_z);
24028 __tmp.put_u32_le(self.failure_flags.bits());
24029 __tmp.put_u16_le(self.flags.bits());
24030 __tmp.put_u8(self.target_system);
24031 __tmp.put_u8(self.target_component);
24032 __tmp.put_f32_le(self.delta_yaw);
24033 __tmp.put_f32_le(self.delta_yaw_velocity);
24034 __tmp.put_u8(self.gimbal_device_id);
24035 if matches!(version, MavlinkVersion::V2) {
24036 let len = __tmp.len();
24037 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24038 } else {
24039 __tmp.len()
24040 }
24041 }
24042}
24043#[doc = "id: 261"]
24044#[doc = "Information about a storage medium. This message is sent in response to a request with MAV_CMD_REQUEST_MESSAGE and whenever the status of the storage changes (STORAGE_STATUS). Use MAV_CMD_REQUEST_MESSAGE.param2 to indicate the index/id of requested storage: 0 for all, 1 for first, 2 for second, etc."]
24045#[derive(Debug, Clone, PartialEq)]
24046#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24047#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24048pub struct STORAGE_INFORMATION_DATA {
24049 #[doc = "Timestamp (time since system boot)."]
24050 pub time_boot_ms: u32,
24051 #[doc = "Total capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored."]
24052 pub total_capacity: f32,
24053 #[doc = "Used capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored."]
24054 pub used_capacity: f32,
24055 #[doc = "Available storage capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored."]
24056 pub available_capacity: f32,
24057 #[doc = "Read speed."]
24058 pub read_speed: f32,
24059 #[doc = "Write speed."]
24060 pub write_speed: f32,
24061 #[doc = "Storage ID (1 for first, 2 for second, etc.)"]
24062 pub storage_id: u8,
24063 #[doc = "Number of storage devices"]
24064 pub storage_count: u8,
24065 #[doc = "Status of storage"]
24066 pub status: StorageStatus,
24067 #[doc = "Type of storage"]
24068 #[cfg_attr(feature = "serde", serde(default))]
24069 pub mavtype: StorageType,
24070 #[doc = "Textual storage name to be used in UI (microSD 1, Internal Memory, etc.) This is a NULL terminated string. If it is exactly 32 characters long, add a terminating NULL. If this string is empty, the generic type is shown to the user."]
24071 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
24072 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
24073 pub name: [u8; 32],
24074 #[doc = "Flags indicating whether this instance is preferred storage for photos, videos, etc. Note: Implementations should initially set the flags on the system-default storage id used for saving media (if possible/supported). This setting can then be overridden using MAV_CMD_SET_STORAGE_USAGE. If the media usage flags are not set, a GCS may assume storage ID 1 is the default storage for all media types."]
24075 #[cfg_attr(feature = "serde", serde(default))]
24076 pub storage_usage: StorageUsageFlag,
24077}
24078impl STORAGE_INFORMATION_DATA {
24079 pub const ENCODED_LEN: usize = 61usize;
24080 pub const DEFAULT: Self = Self {
24081 time_boot_ms: 0_u32,
24082 total_capacity: 0.0_f32,
24083 used_capacity: 0.0_f32,
24084 available_capacity: 0.0_f32,
24085 read_speed: 0.0_f32,
24086 write_speed: 0.0_f32,
24087 storage_id: 0_u8,
24088 storage_count: 0_u8,
24089 status: StorageStatus::DEFAULT,
24090 mavtype: StorageType::DEFAULT,
24091 name: [0_u8; 32usize],
24092 storage_usage: StorageUsageFlag::DEFAULT,
24093 };
24094 #[cfg(feature = "arbitrary")]
24095 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24096 use arbitrary::{Arbitrary, Unstructured};
24097 let mut buf = [0u8; 1024];
24098 rng.fill_bytes(&mut buf);
24099 let mut unstructured = Unstructured::new(&buf);
24100 Self::arbitrary(&mut unstructured).unwrap_or_default()
24101 }
24102}
24103impl Default for STORAGE_INFORMATION_DATA {
24104 fn default() -> Self {
24105 Self::DEFAULT.clone()
24106 }
24107}
24108impl MessageData for STORAGE_INFORMATION_DATA {
24109 type Message = MavMessage;
24110 const ID: u32 = 261u32;
24111 const NAME: &'static str = "STORAGE_INFORMATION";
24112 const EXTRA_CRC: u8 = 179u8;
24113 const ENCODED_LEN: usize = 61usize;
24114 fn deser(
24115 _version: MavlinkVersion,
24116 __input: &[u8],
24117 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24118 let avail_len = __input.len();
24119 let mut payload_buf = [0; Self::ENCODED_LEN];
24120 let mut buf = if avail_len < Self::ENCODED_LEN {
24121 payload_buf[0..avail_len].copy_from_slice(__input);
24122 Bytes::new(&payload_buf)
24123 } else {
24124 Bytes::new(__input)
24125 };
24126 let mut __struct = Self::default();
24127 __struct.time_boot_ms = buf.get_u32_le();
24128 __struct.total_capacity = buf.get_f32_le();
24129 __struct.used_capacity = buf.get_f32_le();
24130 __struct.available_capacity = buf.get_f32_le();
24131 __struct.read_speed = buf.get_f32_le();
24132 __struct.write_speed = buf.get_f32_le();
24133 __struct.storage_id = buf.get_u8();
24134 __struct.storage_count = buf.get_u8();
24135 let tmp = buf.get_u8();
24136 __struct.status =
24137 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
24138 enum_type: "StorageStatus",
24139 value: tmp as u32,
24140 })?;
24141 let tmp = buf.get_u8();
24142 __struct.mavtype =
24143 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
24144 enum_type: "StorageType",
24145 value: tmp as u32,
24146 })?;
24147 for v in &mut __struct.name {
24148 let val = buf.get_u8();
24149 *v = val;
24150 }
24151 let tmp = buf.get_u8();
24152 __struct.storage_usage = StorageUsageFlag::from_bits(tmp & StorageUsageFlag::all().bits())
24153 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
24154 flag_type: "StorageUsageFlag",
24155 value: tmp as u32,
24156 })?;
24157 Ok(__struct)
24158 }
24159 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24160 let mut __tmp = BytesMut::new(bytes);
24161 #[allow(clippy::absurd_extreme_comparisons)]
24162 #[allow(unused_comparisons)]
24163 if __tmp.remaining() < Self::ENCODED_LEN {
24164 panic!(
24165 "buffer is too small (need {} bytes, but got {})",
24166 Self::ENCODED_LEN,
24167 __tmp.remaining(),
24168 )
24169 }
24170 __tmp.put_u32_le(self.time_boot_ms);
24171 __tmp.put_f32_le(self.total_capacity);
24172 __tmp.put_f32_le(self.used_capacity);
24173 __tmp.put_f32_le(self.available_capacity);
24174 __tmp.put_f32_le(self.read_speed);
24175 __tmp.put_f32_le(self.write_speed);
24176 __tmp.put_u8(self.storage_id);
24177 __tmp.put_u8(self.storage_count);
24178 __tmp.put_u8(self.status as u8);
24179 __tmp.put_u8(self.mavtype as u8);
24180 for val in &self.name {
24181 __tmp.put_u8(*val);
24182 }
24183 __tmp.put_u8(self.storage_usage.bits());
24184 if matches!(version, MavlinkVersion::V2) {
24185 let len = __tmp.len();
24186 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24187 } else {
24188 __tmp.len()
24189 }
24190 }
24191}
24192#[doc = "id: 109"]
24193#[doc = "Status generated by radio and injected into MAVLink stream."]
24194#[derive(Debug, Clone, PartialEq)]
24195#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24196#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24197pub struct RADIO_STATUS_DATA {
24198 #[doc = "Count of radio packet receive errors (since boot)."]
24199 pub rxerrors: u16,
24200 #[doc = "Count of error corrected radio packets (since boot)."]
24201 pub fixed: u16,
24202 #[doc = "Local (message sender) received signal strength indication in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown."]
24203 pub rssi: u8,
24204 #[doc = "Remote (message receiver) signal strength indication in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown."]
24205 pub remrssi: u8,
24206 #[doc = "Remaining free transmitter buffer space."]
24207 pub txbuf: u8,
24208 #[doc = "Local background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], UINT8_MAX: invalid/unknown."]
24209 pub noise: u8,
24210 #[doc = "Remote background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], UINT8_MAX: invalid/unknown."]
24211 pub remnoise: u8,
24212}
24213impl RADIO_STATUS_DATA {
24214 pub const ENCODED_LEN: usize = 9usize;
24215 pub const DEFAULT: Self = Self {
24216 rxerrors: 0_u16,
24217 fixed: 0_u16,
24218 rssi: 0_u8,
24219 remrssi: 0_u8,
24220 txbuf: 0_u8,
24221 noise: 0_u8,
24222 remnoise: 0_u8,
24223 };
24224 #[cfg(feature = "arbitrary")]
24225 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24226 use arbitrary::{Arbitrary, Unstructured};
24227 let mut buf = [0u8; 1024];
24228 rng.fill_bytes(&mut buf);
24229 let mut unstructured = Unstructured::new(&buf);
24230 Self::arbitrary(&mut unstructured).unwrap_or_default()
24231 }
24232}
24233impl Default for RADIO_STATUS_DATA {
24234 fn default() -> Self {
24235 Self::DEFAULT.clone()
24236 }
24237}
24238impl MessageData for RADIO_STATUS_DATA {
24239 type Message = MavMessage;
24240 const ID: u32 = 109u32;
24241 const NAME: &'static str = "RADIO_STATUS";
24242 const EXTRA_CRC: u8 = 185u8;
24243 const ENCODED_LEN: usize = 9usize;
24244 fn deser(
24245 _version: MavlinkVersion,
24246 __input: &[u8],
24247 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24248 let avail_len = __input.len();
24249 let mut payload_buf = [0; Self::ENCODED_LEN];
24250 let mut buf = if avail_len < Self::ENCODED_LEN {
24251 payload_buf[0..avail_len].copy_from_slice(__input);
24252 Bytes::new(&payload_buf)
24253 } else {
24254 Bytes::new(__input)
24255 };
24256 let mut __struct = Self::default();
24257 __struct.rxerrors = buf.get_u16_le();
24258 __struct.fixed = buf.get_u16_le();
24259 __struct.rssi = buf.get_u8();
24260 __struct.remrssi = buf.get_u8();
24261 __struct.txbuf = buf.get_u8();
24262 __struct.noise = buf.get_u8();
24263 __struct.remnoise = buf.get_u8();
24264 Ok(__struct)
24265 }
24266 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24267 let mut __tmp = BytesMut::new(bytes);
24268 #[allow(clippy::absurd_extreme_comparisons)]
24269 #[allow(unused_comparisons)]
24270 if __tmp.remaining() < Self::ENCODED_LEN {
24271 panic!(
24272 "buffer is too small (need {} bytes, but got {})",
24273 Self::ENCODED_LEN,
24274 __tmp.remaining(),
24275 )
24276 }
24277 __tmp.put_u16_le(self.rxerrors);
24278 __tmp.put_u16_le(self.fixed);
24279 __tmp.put_u8(self.rssi);
24280 __tmp.put_u8(self.remrssi);
24281 __tmp.put_u8(self.txbuf);
24282 __tmp.put_u8(self.noise);
24283 __tmp.put_u8(self.remnoise);
24284 if matches!(version, MavlinkVersion::V2) {
24285 let len = __tmp.len();
24286 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24287 } else {
24288 __tmp.len()
24289 }
24290 }
24291}
24292#[doc = "id: 396"]
24293#[doc = "Basic component information data. Should be requested using MAV_CMD_REQUEST_MESSAGE on startup, or when required."]
24294#[derive(Debug, Clone, PartialEq)]
24295#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24296#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24297pub struct COMPONENT_INFORMATION_BASIC_DATA {
24298 #[doc = "Component capability flags"]
24299 pub capabilities: MavProtocolCapability,
24300 #[doc = "Timestamp (time since system boot)."]
24301 pub time_boot_ms: u32,
24302 #[doc = "Date of manufacture as a UNIX Epoch time (since 1.1.1970) in seconds."]
24303 pub time_manufacture_s: u32,
24304 #[doc = "Name of the component vendor. Needs to be zero terminated. The field is optional and can be empty/all zeros."]
24305 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
24306 pub vendor_name: [u8; 32],
24307 #[doc = "Name of the component model. Needs to be zero terminated. The field is optional and can be empty/all zeros."]
24308 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
24309 pub model_name: [u8; 32],
24310 #[doc = "Software version. The recommended format is SEMVER: 'major.minor.patch' (any format may be used). The field must be zero terminated if it has a value. The field is optional and can be empty/all zeros."]
24311 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
24312 pub software_version: [u8; 24],
24313 #[doc = "Hardware version. The recommended format is SEMVER: 'major.minor.patch' (any format may be used). The field must be zero terminated if it has a value. The field is optional and can be empty/all zeros."]
24314 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
24315 pub hardware_version: [u8; 24],
24316 #[doc = "Hardware serial number. The field must be zero terminated if it has a value. The field is optional and can be empty/all zeros."]
24317 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
24318 pub serial_number: [u8; 32],
24319}
24320impl COMPONENT_INFORMATION_BASIC_DATA {
24321 pub const ENCODED_LEN: usize = 160usize;
24322 pub const DEFAULT: Self = Self {
24323 capabilities: MavProtocolCapability::DEFAULT,
24324 time_boot_ms: 0_u32,
24325 time_manufacture_s: 0_u32,
24326 vendor_name: [0_u8; 32usize],
24327 model_name: [0_u8; 32usize],
24328 software_version: [0_u8; 24usize],
24329 hardware_version: [0_u8; 24usize],
24330 serial_number: [0_u8; 32usize],
24331 };
24332 #[cfg(feature = "arbitrary")]
24333 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24334 use arbitrary::{Arbitrary, Unstructured};
24335 let mut buf = [0u8; 1024];
24336 rng.fill_bytes(&mut buf);
24337 let mut unstructured = Unstructured::new(&buf);
24338 Self::arbitrary(&mut unstructured).unwrap_or_default()
24339 }
24340}
24341impl Default for COMPONENT_INFORMATION_BASIC_DATA {
24342 fn default() -> Self {
24343 Self::DEFAULT.clone()
24344 }
24345}
24346impl MessageData for COMPONENT_INFORMATION_BASIC_DATA {
24347 type Message = MavMessage;
24348 const ID: u32 = 396u32;
24349 const NAME: &'static str = "COMPONENT_INFORMATION_BASIC";
24350 const EXTRA_CRC: u8 = 50u8;
24351 const ENCODED_LEN: usize = 160usize;
24352 fn deser(
24353 _version: MavlinkVersion,
24354 __input: &[u8],
24355 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24356 let avail_len = __input.len();
24357 let mut payload_buf = [0; Self::ENCODED_LEN];
24358 let mut buf = if avail_len < Self::ENCODED_LEN {
24359 payload_buf[0..avail_len].copy_from_slice(__input);
24360 Bytes::new(&payload_buf)
24361 } else {
24362 Bytes::new(__input)
24363 };
24364 let mut __struct = Self::default();
24365 let tmp = buf.get_u64_le();
24366 __struct.capabilities = MavProtocolCapability::from_bits(
24367 tmp & MavProtocolCapability::all().bits(),
24368 )
24369 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
24370 flag_type: "MavProtocolCapability",
24371 value: tmp as u32,
24372 })?;
24373 __struct.time_boot_ms = buf.get_u32_le();
24374 __struct.time_manufacture_s = buf.get_u32_le();
24375 for v in &mut __struct.vendor_name {
24376 let val = buf.get_u8();
24377 *v = val;
24378 }
24379 for v in &mut __struct.model_name {
24380 let val = buf.get_u8();
24381 *v = val;
24382 }
24383 for v in &mut __struct.software_version {
24384 let val = buf.get_u8();
24385 *v = val;
24386 }
24387 for v in &mut __struct.hardware_version {
24388 let val = buf.get_u8();
24389 *v = val;
24390 }
24391 for v in &mut __struct.serial_number {
24392 let val = buf.get_u8();
24393 *v = val;
24394 }
24395 Ok(__struct)
24396 }
24397 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24398 let mut __tmp = BytesMut::new(bytes);
24399 #[allow(clippy::absurd_extreme_comparisons)]
24400 #[allow(unused_comparisons)]
24401 if __tmp.remaining() < Self::ENCODED_LEN {
24402 panic!(
24403 "buffer is too small (need {} bytes, but got {})",
24404 Self::ENCODED_LEN,
24405 __tmp.remaining(),
24406 )
24407 }
24408 __tmp.put_u64_le(self.capabilities.bits());
24409 __tmp.put_u32_le(self.time_boot_ms);
24410 __tmp.put_u32_le(self.time_manufacture_s);
24411 for val in &self.vendor_name {
24412 __tmp.put_u8(*val);
24413 }
24414 for val in &self.model_name {
24415 __tmp.put_u8(*val);
24416 }
24417 for val in &self.software_version {
24418 __tmp.put_u8(*val);
24419 }
24420 for val in &self.hardware_version {
24421 __tmp.put_u8(*val);
24422 }
24423 for val in &self.serial_number {
24424 __tmp.put_u8(*val);
24425 }
24426 if matches!(version, MavlinkVersion::V2) {
24427 let len = __tmp.len();
24428 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24429 } else {
24430 __tmp.len()
24431 }
24432 }
24433}
24434#[doc = "id: 252"]
24435#[doc = "Send a key-value pair as integer. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output."]
24436#[derive(Debug, Clone, PartialEq)]
24437#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24438#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24439pub struct NAMED_VALUE_INT_DATA {
24440 #[doc = "Timestamp (time since system boot)."]
24441 pub time_boot_ms: u32,
24442 #[doc = "Signed integer value"]
24443 pub value: i32,
24444 #[doc = "Name of the debug variable"]
24445 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
24446 pub name: [u8; 10],
24447}
24448impl NAMED_VALUE_INT_DATA {
24449 pub const ENCODED_LEN: usize = 18usize;
24450 pub const DEFAULT: Self = Self {
24451 time_boot_ms: 0_u32,
24452 value: 0_i32,
24453 name: [0_u8; 10usize],
24454 };
24455 #[cfg(feature = "arbitrary")]
24456 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24457 use arbitrary::{Arbitrary, Unstructured};
24458 let mut buf = [0u8; 1024];
24459 rng.fill_bytes(&mut buf);
24460 let mut unstructured = Unstructured::new(&buf);
24461 Self::arbitrary(&mut unstructured).unwrap_or_default()
24462 }
24463}
24464impl Default for NAMED_VALUE_INT_DATA {
24465 fn default() -> Self {
24466 Self::DEFAULT.clone()
24467 }
24468}
24469impl MessageData for NAMED_VALUE_INT_DATA {
24470 type Message = MavMessage;
24471 const ID: u32 = 252u32;
24472 const NAME: &'static str = "NAMED_VALUE_INT";
24473 const EXTRA_CRC: u8 = 44u8;
24474 const ENCODED_LEN: usize = 18usize;
24475 fn deser(
24476 _version: MavlinkVersion,
24477 __input: &[u8],
24478 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24479 let avail_len = __input.len();
24480 let mut payload_buf = [0; Self::ENCODED_LEN];
24481 let mut buf = if avail_len < Self::ENCODED_LEN {
24482 payload_buf[0..avail_len].copy_from_slice(__input);
24483 Bytes::new(&payload_buf)
24484 } else {
24485 Bytes::new(__input)
24486 };
24487 let mut __struct = Self::default();
24488 __struct.time_boot_ms = buf.get_u32_le();
24489 __struct.value = buf.get_i32_le();
24490 for v in &mut __struct.name {
24491 let val = buf.get_u8();
24492 *v = val;
24493 }
24494 Ok(__struct)
24495 }
24496 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24497 let mut __tmp = BytesMut::new(bytes);
24498 #[allow(clippy::absurd_extreme_comparisons)]
24499 #[allow(unused_comparisons)]
24500 if __tmp.remaining() < Self::ENCODED_LEN {
24501 panic!(
24502 "buffer is too small (need {} bytes, but got {})",
24503 Self::ENCODED_LEN,
24504 __tmp.remaining(),
24505 )
24506 }
24507 __tmp.put_u32_le(self.time_boot_ms);
24508 __tmp.put_i32_le(self.value);
24509 for val in &self.name {
24510 __tmp.put_u8(*val);
24511 }
24512 if matches!(version, MavlinkVersion::V2) {
24513 let len = __tmp.len();
24514 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24515 } else {
24516 __tmp.len()
24517 }
24518 }
24519}
24520#[doc = "id: 122"]
24521#[doc = "Stop log transfer and resume normal logging."]
24522#[derive(Debug, Clone, PartialEq)]
24523#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24524#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24525pub struct LOG_REQUEST_END_DATA {
24526 #[doc = "System ID"]
24527 pub target_system: u8,
24528 #[doc = "Component ID"]
24529 pub target_component: u8,
24530}
24531impl LOG_REQUEST_END_DATA {
24532 pub const ENCODED_LEN: usize = 2usize;
24533 pub const DEFAULT: Self = Self {
24534 target_system: 0_u8,
24535 target_component: 0_u8,
24536 };
24537 #[cfg(feature = "arbitrary")]
24538 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24539 use arbitrary::{Arbitrary, Unstructured};
24540 let mut buf = [0u8; 1024];
24541 rng.fill_bytes(&mut buf);
24542 let mut unstructured = Unstructured::new(&buf);
24543 Self::arbitrary(&mut unstructured).unwrap_or_default()
24544 }
24545}
24546impl Default for LOG_REQUEST_END_DATA {
24547 fn default() -> Self {
24548 Self::DEFAULT.clone()
24549 }
24550}
24551impl MessageData for LOG_REQUEST_END_DATA {
24552 type Message = MavMessage;
24553 const ID: u32 = 122u32;
24554 const NAME: &'static str = "LOG_REQUEST_END";
24555 const EXTRA_CRC: u8 = 203u8;
24556 const ENCODED_LEN: usize = 2usize;
24557 fn deser(
24558 _version: MavlinkVersion,
24559 __input: &[u8],
24560 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24561 let avail_len = __input.len();
24562 let mut payload_buf = [0; Self::ENCODED_LEN];
24563 let mut buf = if avail_len < Self::ENCODED_LEN {
24564 payload_buf[0..avail_len].copy_from_slice(__input);
24565 Bytes::new(&payload_buf)
24566 } else {
24567 Bytes::new(__input)
24568 };
24569 let mut __struct = Self::default();
24570 __struct.target_system = buf.get_u8();
24571 __struct.target_component = buf.get_u8();
24572 Ok(__struct)
24573 }
24574 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24575 let mut __tmp = BytesMut::new(bytes);
24576 #[allow(clippy::absurd_extreme_comparisons)]
24577 #[allow(unused_comparisons)]
24578 if __tmp.remaining() < Self::ENCODED_LEN {
24579 panic!(
24580 "buffer is too small (need {} bytes, but got {})",
24581 Self::ENCODED_LEN,
24582 __tmp.remaining(),
24583 )
24584 }
24585 __tmp.put_u8(self.target_system);
24586 __tmp.put_u8(self.target_component);
24587 if matches!(version, MavlinkVersion::V2) {
24588 let len = __tmp.len();
24589 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24590 } else {
24591 __tmp.len()
24592 }
24593 }
24594}
24595#[doc = "id: 40"]
24596#[doc = "Request the information of the mission item with the sequence number seq. The response of the system to this message should be a MISSION_ITEM message. <https://mavlink.io/en/services/mission.html>."]
24597#[derive(Debug, Clone, PartialEq)]
24598#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24599#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24600pub struct MISSION_REQUEST_DATA {
24601 #[doc = "Sequence"]
24602 pub seq: u16,
24603 #[doc = "System ID"]
24604 pub target_system: u8,
24605 #[doc = "Component ID"]
24606 pub target_component: u8,
24607 #[doc = "Mission type."]
24608 #[cfg_attr(feature = "serde", serde(default))]
24609 pub mission_type: MavMissionType,
24610}
24611impl MISSION_REQUEST_DATA {
24612 pub const ENCODED_LEN: usize = 5usize;
24613 pub const DEFAULT: Self = Self {
24614 seq: 0_u16,
24615 target_system: 0_u8,
24616 target_component: 0_u8,
24617 mission_type: MavMissionType::DEFAULT,
24618 };
24619 #[cfg(feature = "arbitrary")]
24620 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24621 use arbitrary::{Arbitrary, Unstructured};
24622 let mut buf = [0u8; 1024];
24623 rng.fill_bytes(&mut buf);
24624 let mut unstructured = Unstructured::new(&buf);
24625 Self::arbitrary(&mut unstructured).unwrap_or_default()
24626 }
24627}
24628impl Default for MISSION_REQUEST_DATA {
24629 fn default() -> Self {
24630 Self::DEFAULT.clone()
24631 }
24632}
24633impl MessageData for MISSION_REQUEST_DATA {
24634 type Message = MavMessage;
24635 const ID: u32 = 40u32;
24636 const NAME: &'static str = "MISSION_REQUEST";
24637 const EXTRA_CRC: u8 = 230u8;
24638 const ENCODED_LEN: usize = 5usize;
24639 fn deser(
24640 _version: MavlinkVersion,
24641 __input: &[u8],
24642 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24643 let avail_len = __input.len();
24644 let mut payload_buf = [0; Self::ENCODED_LEN];
24645 let mut buf = if avail_len < Self::ENCODED_LEN {
24646 payload_buf[0..avail_len].copy_from_slice(__input);
24647 Bytes::new(&payload_buf)
24648 } else {
24649 Bytes::new(__input)
24650 };
24651 let mut __struct = Self::default();
24652 __struct.seq = buf.get_u16_le();
24653 __struct.target_system = buf.get_u8();
24654 __struct.target_component = buf.get_u8();
24655 let tmp = buf.get_u8();
24656 __struct.mission_type =
24657 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
24658 enum_type: "MavMissionType",
24659 value: tmp as u32,
24660 })?;
24661 Ok(__struct)
24662 }
24663 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24664 let mut __tmp = BytesMut::new(bytes);
24665 #[allow(clippy::absurd_extreme_comparisons)]
24666 #[allow(unused_comparisons)]
24667 if __tmp.remaining() < Self::ENCODED_LEN {
24668 panic!(
24669 "buffer is too small (need {} bytes, but got {})",
24670 Self::ENCODED_LEN,
24671 __tmp.remaining(),
24672 )
24673 }
24674 __tmp.put_u16_le(self.seq);
24675 __tmp.put_u8(self.target_system);
24676 __tmp.put_u8(self.target_component);
24677 __tmp.put_u8(self.mission_type as u8);
24678 if matches!(version, MavlinkVersion::V2) {
24679 let len = __tmp.len();
24680 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24681 } else {
24682 __tmp.len()
24683 }
24684 }
24685}
24686#[doc = "id: 84"]
24687#[doc = "Sets a desired vehicle position in a local north-east-down coordinate frame. Used by an external controller to command the vehicle (manual controller or other system)."]
24688#[derive(Debug, Clone, PartialEq)]
24689#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24690#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24691pub struct SET_POSITION_TARGET_LOCAL_NED_DATA {
24692 #[doc = "Timestamp (time since system boot)."]
24693 pub time_boot_ms: u32,
24694 #[doc = "X Position in NED frame"]
24695 pub x: f32,
24696 #[doc = "Y Position in NED frame"]
24697 pub y: f32,
24698 #[doc = "Z Position in NED frame (note, altitude is negative in NED)"]
24699 pub z: f32,
24700 #[doc = "X velocity in NED frame"]
24701 pub vx: f32,
24702 #[doc = "Y velocity in NED frame"]
24703 pub vy: f32,
24704 #[doc = "Z velocity in NED frame"]
24705 pub vz: f32,
24706 #[doc = "X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
24707 pub afx: f32,
24708 #[doc = "Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
24709 pub afy: f32,
24710 #[doc = "Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
24711 pub afz: f32,
24712 #[doc = "yaw setpoint"]
24713 pub yaw: f32,
24714 #[doc = "yaw rate setpoint"]
24715 pub yaw_rate: f32,
24716 #[doc = "Bitmap to indicate which dimensions should be ignored by the vehicle."]
24717 pub type_mask: PositionTargetTypemask,
24718 #[doc = "System ID"]
24719 pub target_system: u8,
24720 #[doc = "Component ID"]
24721 pub target_component: u8,
24722 #[doc = "Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9"]
24723 pub coordinate_frame: MavFrame,
24724}
24725impl SET_POSITION_TARGET_LOCAL_NED_DATA {
24726 pub const ENCODED_LEN: usize = 53usize;
24727 pub const DEFAULT: Self = Self {
24728 time_boot_ms: 0_u32,
24729 x: 0.0_f32,
24730 y: 0.0_f32,
24731 z: 0.0_f32,
24732 vx: 0.0_f32,
24733 vy: 0.0_f32,
24734 vz: 0.0_f32,
24735 afx: 0.0_f32,
24736 afy: 0.0_f32,
24737 afz: 0.0_f32,
24738 yaw: 0.0_f32,
24739 yaw_rate: 0.0_f32,
24740 type_mask: PositionTargetTypemask::DEFAULT,
24741 target_system: 0_u8,
24742 target_component: 0_u8,
24743 coordinate_frame: MavFrame::DEFAULT,
24744 };
24745 #[cfg(feature = "arbitrary")]
24746 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24747 use arbitrary::{Arbitrary, Unstructured};
24748 let mut buf = [0u8; 1024];
24749 rng.fill_bytes(&mut buf);
24750 let mut unstructured = Unstructured::new(&buf);
24751 Self::arbitrary(&mut unstructured).unwrap_or_default()
24752 }
24753}
24754impl Default for SET_POSITION_TARGET_LOCAL_NED_DATA {
24755 fn default() -> Self {
24756 Self::DEFAULT.clone()
24757 }
24758}
24759impl MessageData for SET_POSITION_TARGET_LOCAL_NED_DATA {
24760 type Message = MavMessage;
24761 const ID: u32 = 84u32;
24762 const NAME: &'static str = "SET_POSITION_TARGET_LOCAL_NED";
24763 const EXTRA_CRC: u8 = 143u8;
24764 const ENCODED_LEN: usize = 53usize;
24765 fn deser(
24766 _version: MavlinkVersion,
24767 __input: &[u8],
24768 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24769 let avail_len = __input.len();
24770 let mut payload_buf = [0; Self::ENCODED_LEN];
24771 let mut buf = if avail_len < Self::ENCODED_LEN {
24772 payload_buf[0..avail_len].copy_from_slice(__input);
24773 Bytes::new(&payload_buf)
24774 } else {
24775 Bytes::new(__input)
24776 };
24777 let mut __struct = Self::default();
24778 __struct.time_boot_ms = buf.get_u32_le();
24779 __struct.x = buf.get_f32_le();
24780 __struct.y = buf.get_f32_le();
24781 __struct.z = buf.get_f32_le();
24782 __struct.vx = buf.get_f32_le();
24783 __struct.vy = buf.get_f32_le();
24784 __struct.vz = buf.get_f32_le();
24785 __struct.afx = buf.get_f32_le();
24786 __struct.afy = buf.get_f32_le();
24787 __struct.afz = buf.get_f32_le();
24788 __struct.yaw = buf.get_f32_le();
24789 __struct.yaw_rate = buf.get_f32_le();
24790 let tmp = buf.get_u16_le();
24791 __struct.type_mask = PositionTargetTypemask::from_bits(
24792 tmp & PositionTargetTypemask::all().bits(),
24793 )
24794 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
24795 flag_type: "PositionTargetTypemask",
24796 value: tmp as u32,
24797 })?;
24798 __struct.target_system = buf.get_u8();
24799 __struct.target_component = buf.get_u8();
24800 let tmp = buf.get_u8();
24801 __struct.coordinate_frame =
24802 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
24803 enum_type: "MavFrame",
24804 value: tmp as u32,
24805 })?;
24806 Ok(__struct)
24807 }
24808 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24809 let mut __tmp = BytesMut::new(bytes);
24810 #[allow(clippy::absurd_extreme_comparisons)]
24811 #[allow(unused_comparisons)]
24812 if __tmp.remaining() < Self::ENCODED_LEN {
24813 panic!(
24814 "buffer is too small (need {} bytes, but got {})",
24815 Self::ENCODED_LEN,
24816 __tmp.remaining(),
24817 )
24818 }
24819 __tmp.put_u32_le(self.time_boot_ms);
24820 __tmp.put_f32_le(self.x);
24821 __tmp.put_f32_le(self.y);
24822 __tmp.put_f32_le(self.z);
24823 __tmp.put_f32_le(self.vx);
24824 __tmp.put_f32_le(self.vy);
24825 __tmp.put_f32_le(self.vz);
24826 __tmp.put_f32_le(self.afx);
24827 __tmp.put_f32_le(self.afy);
24828 __tmp.put_f32_le(self.afz);
24829 __tmp.put_f32_le(self.yaw);
24830 __tmp.put_f32_le(self.yaw_rate);
24831 __tmp.put_u16_le(self.type_mask.bits());
24832 __tmp.put_u8(self.target_system);
24833 __tmp.put_u8(self.target_component);
24834 __tmp.put_u8(self.coordinate_frame as u8);
24835 if matches!(version, MavlinkVersion::V2) {
24836 let len = __tmp.len();
24837 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24838 } else {
24839 __tmp.len()
24840 }
24841 }
24842}
24843#[doc = "id: 268"]
24844#[doc = "An ack for a LOGGING_DATA_ACKED message."]
24845#[derive(Debug, Clone, PartialEq)]
24846#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24847#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24848pub struct LOGGING_ACK_DATA {
24849 #[doc = "sequence number (must match the one in LOGGING_DATA_ACKED)"]
24850 pub sequence: u16,
24851 #[doc = "system ID of the target"]
24852 pub target_system: u8,
24853 #[doc = "component ID of the target"]
24854 pub target_component: u8,
24855}
24856impl LOGGING_ACK_DATA {
24857 pub const ENCODED_LEN: usize = 4usize;
24858 pub const DEFAULT: Self = Self {
24859 sequence: 0_u16,
24860 target_system: 0_u8,
24861 target_component: 0_u8,
24862 };
24863 #[cfg(feature = "arbitrary")]
24864 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24865 use arbitrary::{Arbitrary, Unstructured};
24866 let mut buf = [0u8; 1024];
24867 rng.fill_bytes(&mut buf);
24868 let mut unstructured = Unstructured::new(&buf);
24869 Self::arbitrary(&mut unstructured).unwrap_or_default()
24870 }
24871}
24872impl Default for LOGGING_ACK_DATA {
24873 fn default() -> Self {
24874 Self::DEFAULT.clone()
24875 }
24876}
24877impl MessageData for LOGGING_ACK_DATA {
24878 type Message = MavMessage;
24879 const ID: u32 = 268u32;
24880 const NAME: &'static str = "LOGGING_ACK";
24881 const EXTRA_CRC: u8 = 14u8;
24882 const ENCODED_LEN: usize = 4usize;
24883 fn deser(
24884 _version: MavlinkVersion,
24885 __input: &[u8],
24886 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24887 let avail_len = __input.len();
24888 let mut payload_buf = [0; Self::ENCODED_LEN];
24889 let mut buf = if avail_len < Self::ENCODED_LEN {
24890 payload_buf[0..avail_len].copy_from_slice(__input);
24891 Bytes::new(&payload_buf)
24892 } else {
24893 Bytes::new(__input)
24894 };
24895 let mut __struct = Self::default();
24896 __struct.sequence = buf.get_u16_le();
24897 __struct.target_system = buf.get_u8();
24898 __struct.target_component = buf.get_u8();
24899 Ok(__struct)
24900 }
24901 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24902 let mut __tmp = BytesMut::new(bytes);
24903 #[allow(clippy::absurd_extreme_comparisons)]
24904 #[allow(unused_comparisons)]
24905 if __tmp.remaining() < Self::ENCODED_LEN {
24906 panic!(
24907 "buffer is too small (need {} bytes, but got {})",
24908 Self::ENCODED_LEN,
24909 __tmp.remaining(),
24910 )
24911 }
24912 __tmp.put_u16_le(self.sequence);
24913 __tmp.put_u8(self.target_system);
24914 __tmp.put_u8(self.target_component);
24915 if matches!(version, MavlinkVersion::V2) {
24916 let len = __tmp.len();
24917 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24918 } else {
24919 __tmp.len()
24920 }
24921 }
24922}
24923#[doc = "id: 386"]
24924#[doc = "A forwarded CAN frame as requested by MAV_CMD_CAN_FORWARD."]
24925#[derive(Debug, Clone, PartialEq)]
24926#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24927#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24928pub struct CAN_FRAME_DATA {
24929 #[doc = "Frame ID"]
24930 pub id: u32,
24931 #[doc = "System ID."]
24932 pub target_system: u8,
24933 #[doc = "Component ID."]
24934 pub target_component: u8,
24935 #[doc = "Bus number"]
24936 pub bus: u8,
24937 #[doc = "Frame length"]
24938 pub len: u8,
24939 #[doc = "Frame data"]
24940 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
24941 pub data: [u8; 8],
24942}
24943impl CAN_FRAME_DATA {
24944 pub const ENCODED_LEN: usize = 16usize;
24945 pub const DEFAULT: Self = Self {
24946 id: 0_u32,
24947 target_system: 0_u8,
24948 target_component: 0_u8,
24949 bus: 0_u8,
24950 len: 0_u8,
24951 data: [0_u8; 8usize],
24952 };
24953 #[cfg(feature = "arbitrary")]
24954 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24955 use arbitrary::{Arbitrary, Unstructured};
24956 let mut buf = [0u8; 1024];
24957 rng.fill_bytes(&mut buf);
24958 let mut unstructured = Unstructured::new(&buf);
24959 Self::arbitrary(&mut unstructured).unwrap_or_default()
24960 }
24961}
24962impl Default for CAN_FRAME_DATA {
24963 fn default() -> Self {
24964 Self::DEFAULT.clone()
24965 }
24966}
24967impl MessageData for CAN_FRAME_DATA {
24968 type Message = MavMessage;
24969 const ID: u32 = 386u32;
24970 const NAME: &'static str = "CAN_FRAME";
24971 const EXTRA_CRC: u8 = 132u8;
24972 const ENCODED_LEN: usize = 16usize;
24973 fn deser(
24974 _version: MavlinkVersion,
24975 __input: &[u8],
24976 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24977 let avail_len = __input.len();
24978 let mut payload_buf = [0; Self::ENCODED_LEN];
24979 let mut buf = if avail_len < Self::ENCODED_LEN {
24980 payload_buf[0..avail_len].copy_from_slice(__input);
24981 Bytes::new(&payload_buf)
24982 } else {
24983 Bytes::new(__input)
24984 };
24985 let mut __struct = Self::default();
24986 __struct.id = buf.get_u32_le();
24987 __struct.target_system = buf.get_u8();
24988 __struct.target_component = buf.get_u8();
24989 __struct.bus = buf.get_u8();
24990 __struct.len = buf.get_u8();
24991 for v in &mut __struct.data {
24992 let val = buf.get_u8();
24993 *v = val;
24994 }
24995 Ok(__struct)
24996 }
24997 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24998 let mut __tmp = BytesMut::new(bytes);
24999 #[allow(clippy::absurd_extreme_comparisons)]
25000 #[allow(unused_comparisons)]
25001 if __tmp.remaining() < Self::ENCODED_LEN {
25002 panic!(
25003 "buffer is too small (need {} bytes, but got {})",
25004 Self::ENCODED_LEN,
25005 __tmp.remaining(),
25006 )
25007 }
25008 __tmp.put_u32_le(self.id);
25009 __tmp.put_u8(self.target_system);
25010 __tmp.put_u8(self.target_component);
25011 __tmp.put_u8(self.bus);
25012 __tmp.put_u8(self.len);
25013 for val in &self.data {
25014 __tmp.put_u8(*val);
25015 }
25016 if matches!(version, MavlinkVersion::V2) {
25017 let len = __tmp.len();
25018 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25019 } else {
25020 __tmp.len()
25021 }
25022 }
25023}
25024#[doc = "id: 234"]
25025#[doc = "Message appropriate for high latency connections like Iridium."]
25026#[derive(Debug, Clone, PartialEq)]
25027#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25028#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25029pub struct HIGH_LATENCY_DATA {
25030 #[doc = "A bitfield for use for autopilot-specific flags."]
25031 pub custom_mode: u32,
25032 #[doc = "Latitude"]
25033 pub latitude: i32,
25034 #[doc = "Longitude"]
25035 pub longitude: i32,
25036 #[doc = "roll"]
25037 pub roll: i16,
25038 #[doc = "pitch"]
25039 pub pitch: i16,
25040 #[doc = "heading"]
25041 pub heading: u16,
25042 #[doc = "heading setpoint"]
25043 pub heading_sp: i16,
25044 #[doc = "Altitude above mean sea level"]
25045 pub altitude_amsl: i16,
25046 #[doc = "Altitude setpoint relative to the home position"]
25047 pub altitude_sp: i16,
25048 #[doc = "distance to target"]
25049 pub wp_distance: u16,
25050 #[doc = "Bitmap of enabled system modes."]
25051 pub base_mode: MavModeFlag,
25052 #[doc = "The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown."]
25053 pub landed_state: MavLandedState,
25054 #[doc = "throttle (percentage)"]
25055 pub throttle: i8,
25056 #[doc = "airspeed"]
25057 pub airspeed: u8,
25058 #[doc = "airspeed setpoint"]
25059 pub airspeed_sp: u8,
25060 #[doc = "groundspeed"]
25061 pub groundspeed: u8,
25062 #[doc = "climb rate"]
25063 pub climb_rate: i8,
25064 #[doc = "Number of satellites visible. If unknown, set to UINT8_MAX"]
25065 pub gps_nsat: u8,
25066 #[doc = "GPS Fix type."]
25067 pub gps_fix_type: GpsFixType,
25068 #[doc = "Remaining battery (percentage)"]
25069 pub battery_remaining: u8,
25070 #[doc = "Autopilot temperature (degrees C)"]
25071 pub temperature: i8,
25072 #[doc = "Air temperature (degrees C) from airspeed sensor"]
25073 pub temperature_air: i8,
25074 #[doc = "failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence)"]
25075 pub failsafe: u8,
25076 #[doc = "current waypoint number"]
25077 pub wp_num: u8,
25078}
25079impl HIGH_LATENCY_DATA {
25080 pub const ENCODED_LEN: usize = 40usize;
25081 pub const DEFAULT: Self = Self {
25082 custom_mode: 0_u32,
25083 latitude: 0_i32,
25084 longitude: 0_i32,
25085 roll: 0_i16,
25086 pitch: 0_i16,
25087 heading: 0_u16,
25088 heading_sp: 0_i16,
25089 altitude_amsl: 0_i16,
25090 altitude_sp: 0_i16,
25091 wp_distance: 0_u16,
25092 base_mode: MavModeFlag::DEFAULT,
25093 landed_state: MavLandedState::DEFAULT,
25094 throttle: 0_i8,
25095 airspeed: 0_u8,
25096 airspeed_sp: 0_u8,
25097 groundspeed: 0_u8,
25098 climb_rate: 0_i8,
25099 gps_nsat: 0_u8,
25100 gps_fix_type: GpsFixType::DEFAULT,
25101 battery_remaining: 0_u8,
25102 temperature: 0_i8,
25103 temperature_air: 0_i8,
25104 failsafe: 0_u8,
25105 wp_num: 0_u8,
25106 };
25107 #[cfg(feature = "arbitrary")]
25108 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25109 use arbitrary::{Arbitrary, Unstructured};
25110 let mut buf = [0u8; 1024];
25111 rng.fill_bytes(&mut buf);
25112 let mut unstructured = Unstructured::new(&buf);
25113 Self::arbitrary(&mut unstructured).unwrap_or_default()
25114 }
25115}
25116impl Default for HIGH_LATENCY_DATA {
25117 fn default() -> Self {
25118 Self::DEFAULT.clone()
25119 }
25120}
25121impl MessageData for HIGH_LATENCY_DATA {
25122 type Message = MavMessage;
25123 const ID: u32 = 234u32;
25124 const NAME: &'static str = "HIGH_LATENCY";
25125 const EXTRA_CRC: u8 = 150u8;
25126 const ENCODED_LEN: usize = 40usize;
25127 fn deser(
25128 _version: MavlinkVersion,
25129 __input: &[u8],
25130 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25131 let avail_len = __input.len();
25132 let mut payload_buf = [0; Self::ENCODED_LEN];
25133 let mut buf = if avail_len < Self::ENCODED_LEN {
25134 payload_buf[0..avail_len].copy_from_slice(__input);
25135 Bytes::new(&payload_buf)
25136 } else {
25137 Bytes::new(__input)
25138 };
25139 let mut __struct = Self::default();
25140 __struct.custom_mode = buf.get_u32_le();
25141 __struct.latitude = buf.get_i32_le();
25142 __struct.longitude = buf.get_i32_le();
25143 __struct.roll = buf.get_i16_le();
25144 __struct.pitch = buf.get_i16_le();
25145 __struct.heading = buf.get_u16_le();
25146 __struct.heading_sp = buf.get_i16_le();
25147 __struct.altitude_amsl = buf.get_i16_le();
25148 __struct.altitude_sp = buf.get_i16_le();
25149 __struct.wp_distance = buf.get_u16_le();
25150 let tmp = buf.get_u8();
25151 __struct.base_mode = MavModeFlag::from_bits(tmp & MavModeFlag::all().bits()).ok_or(
25152 ::mavlink_core::error::ParserError::InvalidFlag {
25153 flag_type: "MavModeFlag",
25154 value: tmp as u32,
25155 },
25156 )?;
25157 let tmp = buf.get_u8();
25158 __struct.landed_state =
25159 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
25160 enum_type: "MavLandedState",
25161 value: tmp as u32,
25162 })?;
25163 __struct.throttle = buf.get_i8();
25164 __struct.airspeed = buf.get_u8();
25165 __struct.airspeed_sp = buf.get_u8();
25166 __struct.groundspeed = buf.get_u8();
25167 __struct.climb_rate = buf.get_i8();
25168 __struct.gps_nsat = buf.get_u8();
25169 let tmp = buf.get_u8();
25170 __struct.gps_fix_type =
25171 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
25172 enum_type: "GpsFixType",
25173 value: tmp as u32,
25174 })?;
25175 __struct.battery_remaining = buf.get_u8();
25176 __struct.temperature = buf.get_i8();
25177 __struct.temperature_air = buf.get_i8();
25178 __struct.failsafe = buf.get_u8();
25179 __struct.wp_num = buf.get_u8();
25180 Ok(__struct)
25181 }
25182 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25183 let mut __tmp = BytesMut::new(bytes);
25184 #[allow(clippy::absurd_extreme_comparisons)]
25185 #[allow(unused_comparisons)]
25186 if __tmp.remaining() < Self::ENCODED_LEN {
25187 panic!(
25188 "buffer is too small (need {} bytes, but got {})",
25189 Self::ENCODED_LEN,
25190 __tmp.remaining(),
25191 )
25192 }
25193 __tmp.put_u32_le(self.custom_mode);
25194 __tmp.put_i32_le(self.latitude);
25195 __tmp.put_i32_le(self.longitude);
25196 __tmp.put_i16_le(self.roll);
25197 __tmp.put_i16_le(self.pitch);
25198 __tmp.put_u16_le(self.heading);
25199 __tmp.put_i16_le(self.heading_sp);
25200 __tmp.put_i16_le(self.altitude_amsl);
25201 __tmp.put_i16_le(self.altitude_sp);
25202 __tmp.put_u16_le(self.wp_distance);
25203 __tmp.put_u8(self.base_mode.bits());
25204 __tmp.put_u8(self.landed_state as u8);
25205 __tmp.put_i8(self.throttle);
25206 __tmp.put_u8(self.airspeed);
25207 __tmp.put_u8(self.airspeed_sp);
25208 __tmp.put_u8(self.groundspeed);
25209 __tmp.put_i8(self.climb_rate);
25210 __tmp.put_u8(self.gps_nsat);
25211 __tmp.put_u8(self.gps_fix_type as u8);
25212 __tmp.put_u8(self.battery_remaining);
25213 __tmp.put_i8(self.temperature);
25214 __tmp.put_i8(self.temperature_air);
25215 __tmp.put_u8(self.failsafe);
25216 __tmp.put_u8(self.wp_num);
25217 if matches!(version, MavlinkVersion::V2) {
25218 let len = __tmp.len();
25219 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25220 } else {
25221 __tmp.len()
25222 }
25223 }
25224}
25225#[doc = "id: 241"]
25226#[doc = "Vibration levels and accelerometer clipping."]
25227#[derive(Debug, Clone, PartialEq)]
25228#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25229#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25230pub struct VIBRATION_DATA {
25231 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
25232 pub time_usec: u64,
25233 #[doc = "Vibration levels on X-axis"]
25234 pub vibration_x: f32,
25235 #[doc = "Vibration levels on Y-axis"]
25236 pub vibration_y: f32,
25237 #[doc = "Vibration levels on Z-axis"]
25238 pub vibration_z: f32,
25239 #[doc = "first accelerometer clipping count"]
25240 pub clipping_0: u32,
25241 #[doc = "second accelerometer clipping count"]
25242 pub clipping_1: u32,
25243 #[doc = "third accelerometer clipping count"]
25244 pub clipping_2: u32,
25245}
25246impl VIBRATION_DATA {
25247 pub const ENCODED_LEN: usize = 32usize;
25248 pub const DEFAULT: Self = Self {
25249 time_usec: 0_u64,
25250 vibration_x: 0.0_f32,
25251 vibration_y: 0.0_f32,
25252 vibration_z: 0.0_f32,
25253 clipping_0: 0_u32,
25254 clipping_1: 0_u32,
25255 clipping_2: 0_u32,
25256 };
25257 #[cfg(feature = "arbitrary")]
25258 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25259 use arbitrary::{Arbitrary, Unstructured};
25260 let mut buf = [0u8; 1024];
25261 rng.fill_bytes(&mut buf);
25262 let mut unstructured = Unstructured::new(&buf);
25263 Self::arbitrary(&mut unstructured).unwrap_or_default()
25264 }
25265}
25266impl Default for VIBRATION_DATA {
25267 fn default() -> Self {
25268 Self::DEFAULT.clone()
25269 }
25270}
25271impl MessageData for VIBRATION_DATA {
25272 type Message = MavMessage;
25273 const ID: u32 = 241u32;
25274 const NAME: &'static str = "VIBRATION";
25275 const EXTRA_CRC: u8 = 90u8;
25276 const ENCODED_LEN: usize = 32usize;
25277 fn deser(
25278 _version: MavlinkVersion,
25279 __input: &[u8],
25280 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25281 let avail_len = __input.len();
25282 let mut payload_buf = [0; Self::ENCODED_LEN];
25283 let mut buf = if avail_len < Self::ENCODED_LEN {
25284 payload_buf[0..avail_len].copy_from_slice(__input);
25285 Bytes::new(&payload_buf)
25286 } else {
25287 Bytes::new(__input)
25288 };
25289 let mut __struct = Self::default();
25290 __struct.time_usec = buf.get_u64_le();
25291 __struct.vibration_x = buf.get_f32_le();
25292 __struct.vibration_y = buf.get_f32_le();
25293 __struct.vibration_z = buf.get_f32_le();
25294 __struct.clipping_0 = buf.get_u32_le();
25295 __struct.clipping_1 = buf.get_u32_le();
25296 __struct.clipping_2 = buf.get_u32_le();
25297 Ok(__struct)
25298 }
25299 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25300 let mut __tmp = BytesMut::new(bytes);
25301 #[allow(clippy::absurd_extreme_comparisons)]
25302 #[allow(unused_comparisons)]
25303 if __tmp.remaining() < Self::ENCODED_LEN {
25304 panic!(
25305 "buffer is too small (need {} bytes, but got {})",
25306 Self::ENCODED_LEN,
25307 __tmp.remaining(),
25308 )
25309 }
25310 __tmp.put_u64_le(self.time_usec);
25311 __tmp.put_f32_le(self.vibration_x);
25312 __tmp.put_f32_le(self.vibration_y);
25313 __tmp.put_f32_le(self.vibration_z);
25314 __tmp.put_u32_le(self.clipping_0);
25315 __tmp.put_u32_le(self.clipping_1);
25316 __tmp.put_u32_le(self.clipping_2);
25317 if matches!(version, MavlinkVersion::V2) {
25318 let len = __tmp.len();
25319 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25320 } else {
25321 __tmp.len()
25322 }
25323 }
25324}
25325#[doc = "id: 5"]
25326#[doc = "Request to control this MAV."]
25327#[derive(Debug, Clone, PartialEq)]
25328#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25329#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25330pub struct CHANGE_OPERATOR_CONTROL_DATA {
25331 #[doc = "System the GCS requests control for"]
25332 pub target_system: u8,
25333 #[doc = "0: request control of this MAV, 1: Release control of this MAV"]
25334 pub control_request: u8,
25335 #[doc = "0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch."]
25336 pub version: u8,
25337 #[doc = "Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and \"!?,.-\""]
25338 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
25339 pub passkey: [u8; 25],
25340}
25341impl CHANGE_OPERATOR_CONTROL_DATA {
25342 pub const ENCODED_LEN: usize = 28usize;
25343 pub const DEFAULT: Self = Self {
25344 target_system: 0_u8,
25345 control_request: 0_u8,
25346 version: 0_u8,
25347 passkey: [0_u8; 25usize],
25348 };
25349 #[cfg(feature = "arbitrary")]
25350 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25351 use arbitrary::{Arbitrary, Unstructured};
25352 let mut buf = [0u8; 1024];
25353 rng.fill_bytes(&mut buf);
25354 let mut unstructured = Unstructured::new(&buf);
25355 Self::arbitrary(&mut unstructured).unwrap_or_default()
25356 }
25357}
25358impl Default for CHANGE_OPERATOR_CONTROL_DATA {
25359 fn default() -> Self {
25360 Self::DEFAULT.clone()
25361 }
25362}
25363impl MessageData for CHANGE_OPERATOR_CONTROL_DATA {
25364 type Message = MavMessage;
25365 const ID: u32 = 5u32;
25366 const NAME: &'static str = "CHANGE_OPERATOR_CONTROL";
25367 const EXTRA_CRC: u8 = 217u8;
25368 const ENCODED_LEN: usize = 28usize;
25369 fn deser(
25370 _version: MavlinkVersion,
25371 __input: &[u8],
25372 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25373 let avail_len = __input.len();
25374 let mut payload_buf = [0; Self::ENCODED_LEN];
25375 let mut buf = if avail_len < Self::ENCODED_LEN {
25376 payload_buf[0..avail_len].copy_from_slice(__input);
25377 Bytes::new(&payload_buf)
25378 } else {
25379 Bytes::new(__input)
25380 };
25381 let mut __struct = Self::default();
25382 __struct.target_system = buf.get_u8();
25383 __struct.control_request = buf.get_u8();
25384 __struct.version = buf.get_u8();
25385 for v in &mut __struct.passkey {
25386 let val = buf.get_u8();
25387 *v = val;
25388 }
25389 Ok(__struct)
25390 }
25391 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25392 let mut __tmp = BytesMut::new(bytes);
25393 #[allow(clippy::absurd_extreme_comparisons)]
25394 #[allow(unused_comparisons)]
25395 if __tmp.remaining() < Self::ENCODED_LEN {
25396 panic!(
25397 "buffer is too small (need {} bytes, but got {})",
25398 Self::ENCODED_LEN,
25399 __tmp.remaining(),
25400 )
25401 }
25402 __tmp.put_u8(self.target_system);
25403 __tmp.put_u8(self.control_request);
25404 __tmp.put_u8(self.version);
25405 for val in &self.passkey {
25406 __tmp.put_u8(*val);
25407 }
25408 if matches!(version, MavlinkVersion::V2) {
25409 let len = __tmp.len();
25410 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25411 } else {
25412 __tmp.len()
25413 }
25414 }
25415}
25416#[doc = "id: 81"]
25417#[doc = "Setpoint in roll, pitch, yaw and thrust from the operator."]
25418#[derive(Debug, Clone, PartialEq)]
25419#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25420#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25421pub struct MANUAL_SETPOINT_DATA {
25422 #[doc = "Timestamp (time since system boot)."]
25423 pub time_boot_ms: u32,
25424 #[doc = "Desired roll rate"]
25425 pub roll: f32,
25426 #[doc = "Desired pitch rate"]
25427 pub pitch: f32,
25428 #[doc = "Desired yaw rate"]
25429 pub yaw: f32,
25430 #[doc = "Collective thrust, normalized to 0 .. 1"]
25431 pub thrust: f32,
25432 #[doc = "Flight mode switch position, 0.. 255"]
25433 pub mode_switch: u8,
25434 #[doc = "Override mode switch position, 0.. 255"]
25435 pub manual_override_switch: u8,
25436}
25437impl MANUAL_SETPOINT_DATA {
25438 pub const ENCODED_LEN: usize = 22usize;
25439 pub const DEFAULT: Self = Self {
25440 time_boot_ms: 0_u32,
25441 roll: 0.0_f32,
25442 pitch: 0.0_f32,
25443 yaw: 0.0_f32,
25444 thrust: 0.0_f32,
25445 mode_switch: 0_u8,
25446 manual_override_switch: 0_u8,
25447 };
25448 #[cfg(feature = "arbitrary")]
25449 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25450 use arbitrary::{Arbitrary, Unstructured};
25451 let mut buf = [0u8; 1024];
25452 rng.fill_bytes(&mut buf);
25453 let mut unstructured = Unstructured::new(&buf);
25454 Self::arbitrary(&mut unstructured).unwrap_or_default()
25455 }
25456}
25457impl Default for MANUAL_SETPOINT_DATA {
25458 fn default() -> Self {
25459 Self::DEFAULT.clone()
25460 }
25461}
25462impl MessageData for MANUAL_SETPOINT_DATA {
25463 type Message = MavMessage;
25464 const ID: u32 = 81u32;
25465 const NAME: &'static str = "MANUAL_SETPOINT";
25466 const EXTRA_CRC: u8 = 106u8;
25467 const ENCODED_LEN: usize = 22usize;
25468 fn deser(
25469 _version: MavlinkVersion,
25470 __input: &[u8],
25471 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25472 let avail_len = __input.len();
25473 let mut payload_buf = [0; Self::ENCODED_LEN];
25474 let mut buf = if avail_len < Self::ENCODED_LEN {
25475 payload_buf[0..avail_len].copy_from_slice(__input);
25476 Bytes::new(&payload_buf)
25477 } else {
25478 Bytes::new(__input)
25479 };
25480 let mut __struct = Self::default();
25481 __struct.time_boot_ms = buf.get_u32_le();
25482 __struct.roll = buf.get_f32_le();
25483 __struct.pitch = buf.get_f32_le();
25484 __struct.yaw = buf.get_f32_le();
25485 __struct.thrust = buf.get_f32_le();
25486 __struct.mode_switch = buf.get_u8();
25487 __struct.manual_override_switch = buf.get_u8();
25488 Ok(__struct)
25489 }
25490 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25491 let mut __tmp = BytesMut::new(bytes);
25492 #[allow(clippy::absurd_extreme_comparisons)]
25493 #[allow(unused_comparisons)]
25494 if __tmp.remaining() < Self::ENCODED_LEN {
25495 panic!(
25496 "buffer is too small (need {} bytes, but got {})",
25497 Self::ENCODED_LEN,
25498 __tmp.remaining(),
25499 )
25500 }
25501 __tmp.put_u32_le(self.time_boot_ms);
25502 __tmp.put_f32_le(self.roll);
25503 __tmp.put_f32_le(self.pitch);
25504 __tmp.put_f32_le(self.yaw);
25505 __tmp.put_f32_le(self.thrust);
25506 __tmp.put_u8(self.mode_switch);
25507 __tmp.put_u8(self.manual_override_switch);
25508 if matches!(version, MavlinkVersion::V2) {
25509 let len = __tmp.len();
25510 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25511 } else {
25512 __tmp.len()
25513 }
25514 }
25515}
25516#[doc = "id: 265"]
25517#[doc = "Orientation of a mount."]
25518#[derive(Debug, Clone, PartialEq)]
25519#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25520#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25521pub struct MOUNT_ORIENTATION_DATA {
25522 #[doc = "Timestamp (time since system boot)."]
25523 pub time_boot_ms: u32,
25524 #[doc = "Roll in global frame (set to NaN for invalid)."]
25525 pub roll: f32,
25526 #[doc = "Pitch in global frame (set to NaN for invalid)."]
25527 pub pitch: f32,
25528 #[doc = "Yaw relative to vehicle (set to NaN for invalid)."]
25529 pub yaw: f32,
25530 #[doc = "Yaw in absolute frame relative to Earth's North, north is 0 (set to NaN for invalid)."]
25531 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
25532 pub yaw_absolute: f32,
25533}
25534impl MOUNT_ORIENTATION_DATA {
25535 pub const ENCODED_LEN: usize = 20usize;
25536 pub const DEFAULT: Self = Self {
25537 time_boot_ms: 0_u32,
25538 roll: 0.0_f32,
25539 pitch: 0.0_f32,
25540 yaw: 0.0_f32,
25541 yaw_absolute: 0.0_f32,
25542 };
25543 #[cfg(feature = "arbitrary")]
25544 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25545 use arbitrary::{Arbitrary, Unstructured};
25546 let mut buf = [0u8; 1024];
25547 rng.fill_bytes(&mut buf);
25548 let mut unstructured = Unstructured::new(&buf);
25549 Self::arbitrary(&mut unstructured).unwrap_or_default()
25550 }
25551}
25552impl Default for MOUNT_ORIENTATION_DATA {
25553 fn default() -> Self {
25554 Self::DEFAULT.clone()
25555 }
25556}
25557impl MessageData for MOUNT_ORIENTATION_DATA {
25558 type Message = MavMessage;
25559 const ID: u32 = 265u32;
25560 const NAME: &'static str = "MOUNT_ORIENTATION";
25561 const EXTRA_CRC: u8 = 26u8;
25562 const ENCODED_LEN: usize = 20usize;
25563 fn deser(
25564 _version: MavlinkVersion,
25565 __input: &[u8],
25566 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25567 let avail_len = __input.len();
25568 let mut payload_buf = [0; Self::ENCODED_LEN];
25569 let mut buf = if avail_len < Self::ENCODED_LEN {
25570 payload_buf[0..avail_len].copy_from_slice(__input);
25571 Bytes::new(&payload_buf)
25572 } else {
25573 Bytes::new(__input)
25574 };
25575 let mut __struct = Self::default();
25576 __struct.time_boot_ms = buf.get_u32_le();
25577 __struct.roll = buf.get_f32_le();
25578 __struct.pitch = buf.get_f32_le();
25579 __struct.yaw = buf.get_f32_le();
25580 __struct.yaw_absolute = buf.get_f32_le();
25581 Ok(__struct)
25582 }
25583 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25584 let mut __tmp = BytesMut::new(bytes);
25585 #[allow(clippy::absurd_extreme_comparisons)]
25586 #[allow(unused_comparisons)]
25587 if __tmp.remaining() < Self::ENCODED_LEN {
25588 panic!(
25589 "buffer is too small (need {} bytes, but got {})",
25590 Self::ENCODED_LEN,
25591 __tmp.remaining(),
25592 )
25593 }
25594 __tmp.put_u32_le(self.time_boot_ms);
25595 __tmp.put_f32_le(self.roll);
25596 __tmp.put_f32_le(self.pitch);
25597 __tmp.put_f32_le(self.yaw);
25598 __tmp.put_f32_le(self.yaw_absolute);
25599 if matches!(version, MavlinkVersion::V2) {
25600 let len = __tmp.len();
25601 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25602 } else {
25603 __tmp.len()
25604 }
25605 }
25606}
25607#[doc = "id: 41"]
25608#[doc = "Set the mission item with sequence number seq as the current item and emit MISSION_CURRENT (whether or not the mission number changed). If a mission is currently being executed, the system will continue to this new mission item on the shortest path, skipping any intermediate mission items. Note that mission jump repeat counters are not reset (see MAV_CMD_DO_JUMP param2). This message may trigger a mission state-machine change on some systems: for example from MISSION_STATE_NOT_STARTED or MISSION_STATE_PAUSED to MISSION_STATE_ACTIVE. If the system is in mission mode, on those systems this command might therefore start, restart or resume the mission. If the system is not in mission mode this message must not trigger a switch to mission mode."]
25609#[derive(Debug, Clone, PartialEq)]
25610#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25611#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25612pub struct MISSION_SET_CURRENT_DATA {
25613 #[doc = "Sequence"]
25614 pub seq: u16,
25615 #[doc = "System ID"]
25616 pub target_system: u8,
25617 #[doc = "Component ID"]
25618 pub target_component: u8,
25619}
25620impl MISSION_SET_CURRENT_DATA {
25621 pub const ENCODED_LEN: usize = 4usize;
25622 pub const DEFAULT: Self = Self {
25623 seq: 0_u16,
25624 target_system: 0_u8,
25625 target_component: 0_u8,
25626 };
25627 #[cfg(feature = "arbitrary")]
25628 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25629 use arbitrary::{Arbitrary, Unstructured};
25630 let mut buf = [0u8; 1024];
25631 rng.fill_bytes(&mut buf);
25632 let mut unstructured = Unstructured::new(&buf);
25633 Self::arbitrary(&mut unstructured).unwrap_or_default()
25634 }
25635}
25636impl Default for MISSION_SET_CURRENT_DATA {
25637 fn default() -> Self {
25638 Self::DEFAULT.clone()
25639 }
25640}
25641impl MessageData for MISSION_SET_CURRENT_DATA {
25642 type Message = MavMessage;
25643 const ID: u32 = 41u32;
25644 const NAME: &'static str = "MISSION_SET_CURRENT";
25645 const EXTRA_CRC: u8 = 28u8;
25646 const ENCODED_LEN: usize = 4usize;
25647 fn deser(
25648 _version: MavlinkVersion,
25649 __input: &[u8],
25650 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25651 let avail_len = __input.len();
25652 let mut payload_buf = [0; Self::ENCODED_LEN];
25653 let mut buf = if avail_len < Self::ENCODED_LEN {
25654 payload_buf[0..avail_len].copy_from_slice(__input);
25655 Bytes::new(&payload_buf)
25656 } else {
25657 Bytes::new(__input)
25658 };
25659 let mut __struct = Self::default();
25660 __struct.seq = buf.get_u16_le();
25661 __struct.target_system = buf.get_u8();
25662 __struct.target_component = buf.get_u8();
25663 Ok(__struct)
25664 }
25665 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25666 let mut __tmp = BytesMut::new(bytes);
25667 #[allow(clippy::absurd_extreme_comparisons)]
25668 #[allow(unused_comparisons)]
25669 if __tmp.remaining() < Self::ENCODED_LEN {
25670 panic!(
25671 "buffer is too small (need {} bytes, but got {})",
25672 Self::ENCODED_LEN,
25673 __tmp.remaining(),
25674 )
25675 }
25676 __tmp.put_u16_le(self.seq);
25677 __tmp.put_u8(self.target_system);
25678 __tmp.put_u8(self.target_component);
25679 if matches!(version, MavlinkVersion::V2) {
25680 let len = __tmp.len();
25681 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25682 } else {
25683 __tmp.len()
25684 }
25685 }
25686}
25687#[doc = "id: 27"]
25688#[doc = "The RAW IMU readings for a 9DOF sensor, which is identified by the id (default IMU1). This message should always contain the true raw values without any scaling to allow data capture and system debugging."]
25689#[derive(Debug, Clone, PartialEq)]
25690#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25691#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25692pub struct RAW_IMU_DATA {
25693 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
25694 pub time_usec: u64,
25695 #[doc = "X acceleration (raw)"]
25696 pub xacc: i16,
25697 #[doc = "Y acceleration (raw)"]
25698 pub yacc: i16,
25699 #[doc = "Z acceleration (raw)"]
25700 pub zacc: i16,
25701 #[doc = "Angular speed around X axis (raw)"]
25702 pub xgyro: i16,
25703 #[doc = "Angular speed around Y axis (raw)"]
25704 pub ygyro: i16,
25705 #[doc = "Angular speed around Z axis (raw)"]
25706 pub zgyro: i16,
25707 #[doc = "X Magnetic field (raw)"]
25708 pub xmag: i16,
25709 #[doc = "Y Magnetic field (raw)"]
25710 pub ymag: i16,
25711 #[doc = "Z Magnetic field (raw)"]
25712 pub zmag: i16,
25713 #[doc = "Id. Ids are numbered from 0 and map to IMUs numbered from 1 (e.g. IMU1 will have a message with id=0)"]
25714 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
25715 pub id: u8,
25716 #[doc = "Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C)."]
25717 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
25718 pub temperature: i16,
25719}
25720impl RAW_IMU_DATA {
25721 pub const ENCODED_LEN: usize = 29usize;
25722 pub const DEFAULT: Self = Self {
25723 time_usec: 0_u64,
25724 xacc: 0_i16,
25725 yacc: 0_i16,
25726 zacc: 0_i16,
25727 xgyro: 0_i16,
25728 ygyro: 0_i16,
25729 zgyro: 0_i16,
25730 xmag: 0_i16,
25731 ymag: 0_i16,
25732 zmag: 0_i16,
25733 id: 0_u8,
25734 temperature: 0_i16,
25735 };
25736 #[cfg(feature = "arbitrary")]
25737 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25738 use arbitrary::{Arbitrary, Unstructured};
25739 let mut buf = [0u8; 1024];
25740 rng.fill_bytes(&mut buf);
25741 let mut unstructured = Unstructured::new(&buf);
25742 Self::arbitrary(&mut unstructured).unwrap_or_default()
25743 }
25744}
25745impl Default for RAW_IMU_DATA {
25746 fn default() -> Self {
25747 Self::DEFAULT.clone()
25748 }
25749}
25750impl MessageData for RAW_IMU_DATA {
25751 type Message = MavMessage;
25752 const ID: u32 = 27u32;
25753 const NAME: &'static str = "RAW_IMU";
25754 const EXTRA_CRC: u8 = 144u8;
25755 const ENCODED_LEN: usize = 29usize;
25756 fn deser(
25757 _version: MavlinkVersion,
25758 __input: &[u8],
25759 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25760 let avail_len = __input.len();
25761 let mut payload_buf = [0; Self::ENCODED_LEN];
25762 let mut buf = if avail_len < Self::ENCODED_LEN {
25763 payload_buf[0..avail_len].copy_from_slice(__input);
25764 Bytes::new(&payload_buf)
25765 } else {
25766 Bytes::new(__input)
25767 };
25768 let mut __struct = Self::default();
25769 __struct.time_usec = buf.get_u64_le();
25770 __struct.xacc = buf.get_i16_le();
25771 __struct.yacc = buf.get_i16_le();
25772 __struct.zacc = buf.get_i16_le();
25773 __struct.xgyro = buf.get_i16_le();
25774 __struct.ygyro = buf.get_i16_le();
25775 __struct.zgyro = buf.get_i16_le();
25776 __struct.xmag = buf.get_i16_le();
25777 __struct.ymag = buf.get_i16_le();
25778 __struct.zmag = buf.get_i16_le();
25779 __struct.id = buf.get_u8();
25780 __struct.temperature = buf.get_i16_le();
25781 Ok(__struct)
25782 }
25783 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25784 let mut __tmp = BytesMut::new(bytes);
25785 #[allow(clippy::absurd_extreme_comparisons)]
25786 #[allow(unused_comparisons)]
25787 if __tmp.remaining() < Self::ENCODED_LEN {
25788 panic!(
25789 "buffer is too small (need {} bytes, but got {})",
25790 Self::ENCODED_LEN,
25791 __tmp.remaining(),
25792 )
25793 }
25794 __tmp.put_u64_le(self.time_usec);
25795 __tmp.put_i16_le(self.xacc);
25796 __tmp.put_i16_le(self.yacc);
25797 __tmp.put_i16_le(self.zacc);
25798 __tmp.put_i16_le(self.xgyro);
25799 __tmp.put_i16_le(self.ygyro);
25800 __tmp.put_i16_le(self.zgyro);
25801 __tmp.put_i16_le(self.xmag);
25802 __tmp.put_i16_le(self.ymag);
25803 __tmp.put_i16_le(self.zmag);
25804 __tmp.put_u8(self.id);
25805 __tmp.put_i16_le(self.temperature);
25806 if matches!(version, MavlinkVersion::V2) {
25807 let len = __tmp.len();
25808 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25809 } else {
25810 __tmp.len()
25811 }
25812 }
25813}
25814#[doc = "id: 28"]
25815#[doc = "The RAW pressure readings for the typical setup of one absolute pressure and one differential pressure sensor. The sensor values should be the raw, UNSCALED ADC values."]
25816#[derive(Debug, Clone, PartialEq)]
25817#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25818#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25819pub struct RAW_PRESSURE_DATA {
25820 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
25821 pub time_usec: u64,
25822 #[doc = "Absolute pressure (raw)"]
25823 pub press_abs: i16,
25824 #[doc = "Differential pressure 1 (raw, 0 if nonexistent)"]
25825 pub press_diff1: i16,
25826 #[doc = "Differential pressure 2 (raw, 0 if nonexistent)"]
25827 pub press_diff2: i16,
25828 #[doc = "Raw Temperature measurement (raw)"]
25829 pub temperature: i16,
25830}
25831impl RAW_PRESSURE_DATA {
25832 pub const ENCODED_LEN: usize = 16usize;
25833 pub const DEFAULT: Self = Self {
25834 time_usec: 0_u64,
25835 press_abs: 0_i16,
25836 press_diff1: 0_i16,
25837 press_diff2: 0_i16,
25838 temperature: 0_i16,
25839 };
25840 #[cfg(feature = "arbitrary")]
25841 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25842 use arbitrary::{Arbitrary, Unstructured};
25843 let mut buf = [0u8; 1024];
25844 rng.fill_bytes(&mut buf);
25845 let mut unstructured = Unstructured::new(&buf);
25846 Self::arbitrary(&mut unstructured).unwrap_or_default()
25847 }
25848}
25849impl Default for RAW_PRESSURE_DATA {
25850 fn default() -> Self {
25851 Self::DEFAULT.clone()
25852 }
25853}
25854impl MessageData for RAW_PRESSURE_DATA {
25855 type Message = MavMessage;
25856 const ID: u32 = 28u32;
25857 const NAME: &'static str = "RAW_PRESSURE";
25858 const EXTRA_CRC: u8 = 67u8;
25859 const ENCODED_LEN: usize = 16usize;
25860 fn deser(
25861 _version: MavlinkVersion,
25862 __input: &[u8],
25863 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25864 let avail_len = __input.len();
25865 let mut payload_buf = [0; Self::ENCODED_LEN];
25866 let mut buf = if avail_len < Self::ENCODED_LEN {
25867 payload_buf[0..avail_len].copy_from_slice(__input);
25868 Bytes::new(&payload_buf)
25869 } else {
25870 Bytes::new(__input)
25871 };
25872 let mut __struct = Self::default();
25873 __struct.time_usec = buf.get_u64_le();
25874 __struct.press_abs = buf.get_i16_le();
25875 __struct.press_diff1 = buf.get_i16_le();
25876 __struct.press_diff2 = buf.get_i16_le();
25877 __struct.temperature = buf.get_i16_le();
25878 Ok(__struct)
25879 }
25880 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25881 let mut __tmp = BytesMut::new(bytes);
25882 #[allow(clippy::absurd_extreme_comparisons)]
25883 #[allow(unused_comparisons)]
25884 if __tmp.remaining() < Self::ENCODED_LEN {
25885 panic!(
25886 "buffer is too small (need {} bytes, but got {})",
25887 Self::ENCODED_LEN,
25888 __tmp.remaining(),
25889 )
25890 }
25891 __tmp.put_u64_le(self.time_usec);
25892 __tmp.put_i16_le(self.press_abs);
25893 __tmp.put_i16_le(self.press_diff1);
25894 __tmp.put_i16_le(self.press_diff2);
25895 __tmp.put_i16_le(self.temperature);
25896 if matches!(version, MavlinkVersion::V2) {
25897 let len = __tmp.len();
25898 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25899 } else {
25900 __tmp.len()
25901 }
25902 }
25903}
25904#[doc = "id: 67"]
25905#[doc = "Data stream status information."]
25906#[derive(Debug, Clone, PartialEq)]
25907#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25908#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25909pub struct DATA_STREAM_DATA {
25910 #[doc = "The message rate"]
25911 pub message_rate: u16,
25912 #[doc = "The ID of the requested data stream"]
25913 pub stream_id: u8,
25914 #[doc = "1 stream is enabled, 0 stream is stopped."]
25915 pub on_off: u8,
25916}
25917impl DATA_STREAM_DATA {
25918 pub const ENCODED_LEN: usize = 4usize;
25919 pub const DEFAULT: Self = Self {
25920 message_rate: 0_u16,
25921 stream_id: 0_u8,
25922 on_off: 0_u8,
25923 };
25924 #[cfg(feature = "arbitrary")]
25925 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25926 use arbitrary::{Arbitrary, Unstructured};
25927 let mut buf = [0u8; 1024];
25928 rng.fill_bytes(&mut buf);
25929 let mut unstructured = Unstructured::new(&buf);
25930 Self::arbitrary(&mut unstructured).unwrap_or_default()
25931 }
25932}
25933impl Default for DATA_STREAM_DATA {
25934 fn default() -> Self {
25935 Self::DEFAULT.clone()
25936 }
25937}
25938impl MessageData for DATA_STREAM_DATA {
25939 type Message = MavMessage;
25940 const ID: u32 = 67u32;
25941 const NAME: &'static str = "DATA_STREAM";
25942 const EXTRA_CRC: u8 = 21u8;
25943 const ENCODED_LEN: usize = 4usize;
25944 fn deser(
25945 _version: MavlinkVersion,
25946 __input: &[u8],
25947 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25948 let avail_len = __input.len();
25949 let mut payload_buf = [0; Self::ENCODED_LEN];
25950 let mut buf = if avail_len < Self::ENCODED_LEN {
25951 payload_buf[0..avail_len].copy_from_slice(__input);
25952 Bytes::new(&payload_buf)
25953 } else {
25954 Bytes::new(__input)
25955 };
25956 let mut __struct = Self::default();
25957 __struct.message_rate = buf.get_u16_le();
25958 __struct.stream_id = buf.get_u8();
25959 __struct.on_off = buf.get_u8();
25960 Ok(__struct)
25961 }
25962 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25963 let mut __tmp = BytesMut::new(bytes);
25964 #[allow(clippy::absurd_extreme_comparisons)]
25965 #[allow(unused_comparisons)]
25966 if __tmp.remaining() < Self::ENCODED_LEN {
25967 panic!(
25968 "buffer is too small (need {} bytes, but got {})",
25969 Self::ENCODED_LEN,
25970 __tmp.remaining(),
25971 )
25972 }
25973 __tmp.put_u16_le(self.message_rate);
25974 __tmp.put_u8(self.stream_id);
25975 __tmp.put_u8(self.on_off);
25976 if matches!(version, MavlinkVersion::V2) {
25977 let len = __tmp.len();
25978 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25979 } else {
25980 __tmp.len()
25981 }
25982 }
25983}
25984#[doc = "id: 12901"]
25985#[doc = "Data for filling the OpenDroneID Location message. The float data types are 32-bit IEEE 754. The Location message provides the location, altitude, direction and speed of the aircraft."]
25986#[derive(Debug, Clone, PartialEq)]
25987#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25988#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25989pub struct OPEN_DRONE_ID_LOCATION_DATA {
25990 #[doc = "Current latitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon)."]
25991 pub latitude: i32,
25992 #[doc = "Current longitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon)."]
25993 pub longitude: i32,
25994 #[doc = "The altitude calculated from the barometric pressue. Reference is against 29.92inHg or 1013.2mb. If unknown: -1000 m."]
25995 pub altitude_barometric: f32,
25996 #[doc = "The geodetic altitude as defined by WGS84. If unknown: -1000 m."]
25997 pub altitude_geodetic: f32,
25998 #[doc = "The current height of the unmanned aircraft above the take-off location or the ground as indicated by height_reference. If unknown: -1000 m."]
25999 pub height: f32,
26000 #[doc = "Seconds after the full hour with reference to UTC time. Typically the GPS outputs a time-of-week value in milliseconds. First convert that to UTC and then convert for this field using ((float) (time_week_ms % (60*60*1000))) / 1000. If unknown: 0xFFFF."]
26001 pub timestamp: f32,
26002 #[doc = "Direction over ground (not heading, but direction of movement) measured clockwise from true North: 0 - 35999 centi-degrees. If unknown: 36100 centi-degrees."]
26003 pub direction: u16,
26004 #[doc = "Ground speed. Positive only. If unknown: 25500 cm/s. If speed is larger than 25425 cm/s, use 25425 cm/s."]
26005 pub speed_horizontal: u16,
26006 #[doc = "The vertical speed. Up is positive. If unknown: 6300 cm/s. If speed is larger than 6200 cm/s, use 6200 cm/s. If lower than -6200 cm/s, use -6200 cm/s."]
26007 pub speed_vertical: i16,
26008 #[doc = "System ID (0 for broadcast)."]
26009 pub target_system: u8,
26010 #[doc = "Component ID (0 for broadcast)."]
26011 pub target_component: u8,
26012 #[doc = "Only used for drone ID data received from other UAs. See detailed description at <https://mavlink.io/en/services/opendroneid.html>."]
26013 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
26014 pub id_or_mac: [u8; 20],
26015 #[doc = "Indicates whether the unmanned aircraft is on the ground or in the air."]
26016 pub status: MavOdidStatus,
26017 #[doc = "Indicates the reference point for the height field."]
26018 pub height_reference: MavOdidHeightRef,
26019 #[doc = "The accuracy of the horizontal position."]
26020 pub horizontal_accuracy: MavOdidHorAcc,
26021 #[doc = "The accuracy of the vertical position."]
26022 pub vertical_accuracy: MavOdidVerAcc,
26023 #[doc = "The accuracy of the barometric altitude."]
26024 pub barometer_accuracy: MavOdidVerAcc,
26025 #[doc = "The accuracy of the horizontal and vertical speed."]
26026 pub speed_accuracy: MavOdidSpeedAcc,
26027 #[doc = "The accuracy of the timestamps."]
26028 pub timestamp_accuracy: MavOdidTimeAcc,
26029}
26030impl OPEN_DRONE_ID_LOCATION_DATA {
26031 pub const ENCODED_LEN: usize = 59usize;
26032 pub const DEFAULT: Self = Self {
26033 latitude: 0_i32,
26034 longitude: 0_i32,
26035 altitude_barometric: 0.0_f32,
26036 altitude_geodetic: 0.0_f32,
26037 height: 0.0_f32,
26038 timestamp: 0.0_f32,
26039 direction: 0_u16,
26040 speed_horizontal: 0_u16,
26041 speed_vertical: 0_i16,
26042 target_system: 0_u8,
26043 target_component: 0_u8,
26044 id_or_mac: [0_u8; 20usize],
26045 status: MavOdidStatus::DEFAULT,
26046 height_reference: MavOdidHeightRef::DEFAULT,
26047 horizontal_accuracy: MavOdidHorAcc::DEFAULT,
26048 vertical_accuracy: MavOdidVerAcc::DEFAULT,
26049 barometer_accuracy: MavOdidVerAcc::DEFAULT,
26050 speed_accuracy: MavOdidSpeedAcc::DEFAULT,
26051 timestamp_accuracy: MavOdidTimeAcc::DEFAULT,
26052 };
26053 #[cfg(feature = "arbitrary")]
26054 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
26055 use arbitrary::{Arbitrary, Unstructured};
26056 let mut buf = [0u8; 1024];
26057 rng.fill_bytes(&mut buf);
26058 let mut unstructured = Unstructured::new(&buf);
26059 Self::arbitrary(&mut unstructured).unwrap_or_default()
26060 }
26061}
26062impl Default for OPEN_DRONE_ID_LOCATION_DATA {
26063 fn default() -> Self {
26064 Self::DEFAULT.clone()
26065 }
26066}
26067impl MessageData for OPEN_DRONE_ID_LOCATION_DATA {
26068 type Message = MavMessage;
26069 const ID: u32 = 12901u32;
26070 const NAME: &'static str = "OPEN_DRONE_ID_LOCATION";
26071 const EXTRA_CRC: u8 = 254u8;
26072 const ENCODED_LEN: usize = 59usize;
26073 fn deser(
26074 _version: MavlinkVersion,
26075 __input: &[u8],
26076 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26077 let avail_len = __input.len();
26078 let mut payload_buf = [0; Self::ENCODED_LEN];
26079 let mut buf = if avail_len < Self::ENCODED_LEN {
26080 payload_buf[0..avail_len].copy_from_slice(__input);
26081 Bytes::new(&payload_buf)
26082 } else {
26083 Bytes::new(__input)
26084 };
26085 let mut __struct = Self::default();
26086 __struct.latitude = buf.get_i32_le();
26087 __struct.longitude = buf.get_i32_le();
26088 __struct.altitude_barometric = buf.get_f32_le();
26089 __struct.altitude_geodetic = buf.get_f32_le();
26090 __struct.height = buf.get_f32_le();
26091 __struct.timestamp = buf.get_f32_le();
26092 __struct.direction = buf.get_u16_le();
26093 __struct.speed_horizontal = buf.get_u16_le();
26094 __struct.speed_vertical = buf.get_i16_le();
26095 __struct.target_system = buf.get_u8();
26096 __struct.target_component = buf.get_u8();
26097 for v in &mut __struct.id_or_mac {
26098 let val = buf.get_u8();
26099 *v = val;
26100 }
26101 let tmp = buf.get_u8();
26102 __struct.status =
26103 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
26104 enum_type: "MavOdidStatus",
26105 value: tmp as u32,
26106 })?;
26107 let tmp = buf.get_u8();
26108 __struct.height_reference =
26109 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
26110 enum_type: "MavOdidHeightRef",
26111 value: tmp as u32,
26112 })?;
26113 let tmp = buf.get_u8();
26114 __struct.horizontal_accuracy =
26115 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
26116 enum_type: "MavOdidHorAcc",
26117 value: tmp as u32,
26118 })?;
26119 let tmp = buf.get_u8();
26120 __struct.vertical_accuracy =
26121 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
26122 enum_type: "MavOdidVerAcc",
26123 value: tmp as u32,
26124 })?;
26125 let tmp = buf.get_u8();
26126 __struct.barometer_accuracy =
26127 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
26128 enum_type: "MavOdidVerAcc",
26129 value: tmp as u32,
26130 })?;
26131 let tmp = buf.get_u8();
26132 __struct.speed_accuracy =
26133 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
26134 enum_type: "MavOdidSpeedAcc",
26135 value: tmp as u32,
26136 })?;
26137 let tmp = buf.get_u8();
26138 __struct.timestamp_accuracy =
26139 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
26140 enum_type: "MavOdidTimeAcc",
26141 value: tmp as u32,
26142 })?;
26143 Ok(__struct)
26144 }
26145 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
26146 let mut __tmp = BytesMut::new(bytes);
26147 #[allow(clippy::absurd_extreme_comparisons)]
26148 #[allow(unused_comparisons)]
26149 if __tmp.remaining() < Self::ENCODED_LEN {
26150 panic!(
26151 "buffer is too small (need {} bytes, but got {})",
26152 Self::ENCODED_LEN,
26153 __tmp.remaining(),
26154 )
26155 }
26156 __tmp.put_i32_le(self.latitude);
26157 __tmp.put_i32_le(self.longitude);
26158 __tmp.put_f32_le(self.altitude_barometric);
26159 __tmp.put_f32_le(self.altitude_geodetic);
26160 __tmp.put_f32_le(self.height);
26161 __tmp.put_f32_le(self.timestamp);
26162 __tmp.put_u16_le(self.direction);
26163 __tmp.put_u16_le(self.speed_horizontal);
26164 __tmp.put_i16_le(self.speed_vertical);
26165 __tmp.put_u8(self.target_system);
26166 __tmp.put_u8(self.target_component);
26167 for val in &self.id_or_mac {
26168 __tmp.put_u8(*val);
26169 }
26170 __tmp.put_u8(self.status as u8);
26171 __tmp.put_u8(self.height_reference as u8);
26172 __tmp.put_u8(self.horizontal_accuracy as u8);
26173 __tmp.put_u8(self.vertical_accuracy as u8);
26174 __tmp.put_u8(self.barometer_accuracy as u8);
26175 __tmp.put_u8(self.speed_accuracy as u8);
26176 __tmp.put_u8(self.timestamp_accuracy as u8);
26177 if matches!(version, MavlinkVersion::V2) {
26178 let len = __tmp.len();
26179 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
26180 } else {
26181 __tmp.len()
26182 }
26183 }
26184}
26185#[doc = "id: 385"]
26186#[doc = "Message for transporting \"arbitrary\" variable-length data from one component to another (broadcast is not forbidden, but discouraged). The encoding of the data is usually extension specific, i.e. determined by the source, and is usually not documented as part of the MAVLink specification."]
26187#[derive(Debug, Clone, PartialEq)]
26188#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
26189#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
26190pub struct TUNNEL_DATA {
26191 #[doc = "A code that identifies the content of the payload (0 for unknown, which is the default). If this code is less than 32768, it is a 'registered' payload type and the corresponding code should be added to the MAV_TUNNEL_PAYLOAD_TYPE enum. Software creators can register blocks of types as needed. Codes greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase."]
26192 pub payload_type: MavTunnelPayloadType,
26193 #[doc = "System ID (can be 0 for broadcast, but this is discouraged)"]
26194 pub target_system: u8,
26195 #[doc = "Component ID (can be 0 for broadcast, but this is discouraged)"]
26196 pub target_component: u8,
26197 #[doc = "Length of the data transported in payload"]
26198 pub payload_length: u8,
26199 #[doc = "Variable length payload. The payload length is defined by payload_length. The entire content of this block is opaque unless you understand the encoding specified by payload_type."]
26200 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
26201 pub payload: [u8; 128],
26202}
26203impl TUNNEL_DATA {
26204 pub const ENCODED_LEN: usize = 133usize;
26205 pub const DEFAULT: Self = Self {
26206 payload_type: MavTunnelPayloadType::DEFAULT,
26207 target_system: 0_u8,
26208 target_component: 0_u8,
26209 payload_length: 0_u8,
26210 payload: [0_u8; 128usize],
26211 };
26212 #[cfg(feature = "arbitrary")]
26213 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
26214 use arbitrary::{Arbitrary, Unstructured};
26215 let mut buf = [0u8; 1024];
26216 rng.fill_bytes(&mut buf);
26217 let mut unstructured = Unstructured::new(&buf);
26218 Self::arbitrary(&mut unstructured).unwrap_or_default()
26219 }
26220}
26221impl Default for TUNNEL_DATA {
26222 fn default() -> Self {
26223 Self::DEFAULT.clone()
26224 }
26225}
26226impl MessageData for TUNNEL_DATA {
26227 type Message = MavMessage;
26228 const ID: u32 = 385u32;
26229 const NAME: &'static str = "TUNNEL";
26230 const EXTRA_CRC: u8 = 147u8;
26231 const ENCODED_LEN: usize = 133usize;
26232 fn deser(
26233 _version: MavlinkVersion,
26234 __input: &[u8],
26235 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26236 let avail_len = __input.len();
26237 let mut payload_buf = [0; Self::ENCODED_LEN];
26238 let mut buf = if avail_len < Self::ENCODED_LEN {
26239 payload_buf[0..avail_len].copy_from_slice(__input);
26240 Bytes::new(&payload_buf)
26241 } else {
26242 Bytes::new(__input)
26243 };
26244 let mut __struct = Self::default();
26245 let tmp = buf.get_u16_le();
26246 __struct.payload_type = FromPrimitive::from_u16(tmp).ok_or(
26247 ::mavlink_core::error::ParserError::InvalidEnum {
26248 enum_type: "MavTunnelPayloadType",
26249 value: tmp as u32,
26250 },
26251 )?;
26252 __struct.target_system = buf.get_u8();
26253 __struct.target_component = buf.get_u8();
26254 __struct.payload_length = buf.get_u8();
26255 for v in &mut __struct.payload {
26256 let val = buf.get_u8();
26257 *v = val;
26258 }
26259 Ok(__struct)
26260 }
26261 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
26262 let mut __tmp = BytesMut::new(bytes);
26263 #[allow(clippy::absurd_extreme_comparisons)]
26264 #[allow(unused_comparisons)]
26265 if __tmp.remaining() < Self::ENCODED_LEN {
26266 panic!(
26267 "buffer is too small (need {} bytes, but got {})",
26268 Self::ENCODED_LEN,
26269 __tmp.remaining(),
26270 )
26271 }
26272 __tmp.put_u16_le(self.payload_type as u16);
26273 __tmp.put_u8(self.target_system);
26274 __tmp.put_u8(self.target_component);
26275 __tmp.put_u8(self.payload_length);
26276 for val in &self.payload {
26277 __tmp.put_u8(*val);
26278 }
26279 if matches!(version, MavlinkVersion::V2) {
26280 let len = __tmp.len();
26281 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
26282 } else {
26283 __tmp.len()
26284 }
26285 }
26286}
26287#[doc = "id: 251"]
26288#[doc = "Send a key-value pair as float. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output."]
26289#[derive(Debug, Clone, PartialEq)]
26290#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
26291#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
26292pub struct NAMED_VALUE_FLOAT_DATA {
26293 #[doc = "Timestamp (time since system boot)."]
26294 pub time_boot_ms: u32,
26295 #[doc = "Floating point value"]
26296 pub value: f32,
26297 #[doc = "Name of the debug variable"]
26298 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
26299 pub name: [u8; 10],
26300}
26301impl NAMED_VALUE_FLOAT_DATA {
26302 pub const ENCODED_LEN: usize = 18usize;
26303 pub const DEFAULT: Self = Self {
26304 time_boot_ms: 0_u32,
26305 value: 0.0_f32,
26306 name: [0_u8; 10usize],
26307 };
26308 #[cfg(feature = "arbitrary")]
26309 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
26310 use arbitrary::{Arbitrary, Unstructured};
26311 let mut buf = [0u8; 1024];
26312 rng.fill_bytes(&mut buf);
26313 let mut unstructured = Unstructured::new(&buf);
26314 Self::arbitrary(&mut unstructured).unwrap_or_default()
26315 }
26316}
26317impl Default for NAMED_VALUE_FLOAT_DATA {
26318 fn default() -> Self {
26319 Self::DEFAULT.clone()
26320 }
26321}
26322impl MessageData for NAMED_VALUE_FLOAT_DATA {
26323 type Message = MavMessage;
26324 const ID: u32 = 251u32;
26325 const NAME: &'static str = "NAMED_VALUE_FLOAT";
26326 const EXTRA_CRC: u8 = 170u8;
26327 const ENCODED_LEN: usize = 18usize;
26328 fn deser(
26329 _version: MavlinkVersion,
26330 __input: &[u8],
26331 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26332 let avail_len = __input.len();
26333 let mut payload_buf = [0; Self::ENCODED_LEN];
26334 let mut buf = if avail_len < Self::ENCODED_LEN {
26335 payload_buf[0..avail_len].copy_from_slice(__input);
26336 Bytes::new(&payload_buf)
26337 } else {
26338 Bytes::new(__input)
26339 };
26340 let mut __struct = Self::default();
26341 __struct.time_boot_ms = buf.get_u32_le();
26342 __struct.value = buf.get_f32_le();
26343 for v in &mut __struct.name {
26344 let val = buf.get_u8();
26345 *v = val;
26346 }
26347 Ok(__struct)
26348 }
26349 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
26350 let mut __tmp = BytesMut::new(bytes);
26351 #[allow(clippy::absurd_extreme_comparisons)]
26352 #[allow(unused_comparisons)]
26353 if __tmp.remaining() < Self::ENCODED_LEN {
26354 panic!(
26355 "buffer is too small (need {} bytes, but got {})",
26356 Self::ENCODED_LEN,
26357 __tmp.remaining(),
26358 )
26359 }
26360 __tmp.put_u32_le(self.time_boot_ms);
26361 __tmp.put_f32_le(self.value);
26362 for val in &self.name {
26363 __tmp.put_u8(*val);
26364 }
26365 if matches!(version, MavlinkVersion::V2) {
26366 let len = __tmp.len();
26367 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
26368 } else {
26369 __tmp.len()
26370 }
26371 }
26372}
26373#[doc = "id: 108"]
26374#[doc = "Status of simulation environment, if used."]
26375#[derive(Debug, Clone, PartialEq)]
26376#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
26377#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
26378pub struct SIM_STATE_DATA {
26379 #[doc = "True attitude quaternion component 1, w (1 in null-rotation)"]
26380 pub q1: f32,
26381 #[doc = "True attitude quaternion component 2, x (0 in null-rotation)"]
26382 pub q2: f32,
26383 #[doc = "True attitude quaternion component 3, y (0 in null-rotation)"]
26384 pub q3: f32,
26385 #[doc = "True attitude quaternion component 4, z (0 in null-rotation)"]
26386 pub q4: f32,
26387 #[doc = "Attitude roll expressed as Euler angles, not recommended except for human-readable outputs"]
26388 pub roll: f32,
26389 #[doc = "Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs"]
26390 pub pitch: f32,
26391 #[doc = "Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs"]
26392 pub yaw: f32,
26393 #[doc = "X acceleration"]
26394 pub xacc: f32,
26395 #[doc = "Y acceleration"]
26396 pub yacc: f32,
26397 #[doc = "Z acceleration"]
26398 pub zacc: f32,
26399 #[doc = "Angular speed around X axis"]
26400 pub xgyro: f32,
26401 #[doc = "Angular speed around Y axis"]
26402 pub ygyro: f32,
26403 #[doc = "Angular speed around Z axis"]
26404 pub zgyro: f32,
26405 #[doc = "Latitude (lower precision). Both this and the lat_int field should be set."]
26406 pub lat: f32,
26407 #[doc = "Longitude (lower precision). Both this and the lon_int field should be set."]
26408 pub lon: f32,
26409 #[doc = "Altitude"]
26410 pub alt: f32,
26411 #[doc = "Horizontal position standard deviation"]
26412 pub std_dev_horz: f32,
26413 #[doc = "Vertical position standard deviation"]
26414 pub std_dev_vert: f32,
26415 #[doc = "True velocity in north direction in earth-fixed NED frame"]
26416 pub vn: f32,
26417 #[doc = "True velocity in east direction in earth-fixed NED frame"]
26418 pub ve: f32,
26419 #[doc = "True velocity in down direction in earth-fixed NED frame"]
26420 pub vd: f32,
26421 #[doc = "Latitude (higher precision). If 0, recipients should use the lat field value (otherwise this field is preferred)."]
26422 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
26423 pub lat_int: i32,
26424 #[doc = "Longitude (higher precision). If 0, recipients should use the lon field value (otherwise this field is preferred)."]
26425 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
26426 pub lon_int: i32,
26427}
26428impl SIM_STATE_DATA {
26429 pub const ENCODED_LEN: usize = 92usize;
26430 pub const DEFAULT: Self = Self {
26431 q1: 0.0_f32,
26432 q2: 0.0_f32,
26433 q3: 0.0_f32,
26434 q4: 0.0_f32,
26435 roll: 0.0_f32,
26436 pitch: 0.0_f32,
26437 yaw: 0.0_f32,
26438 xacc: 0.0_f32,
26439 yacc: 0.0_f32,
26440 zacc: 0.0_f32,
26441 xgyro: 0.0_f32,
26442 ygyro: 0.0_f32,
26443 zgyro: 0.0_f32,
26444 lat: 0.0_f32,
26445 lon: 0.0_f32,
26446 alt: 0.0_f32,
26447 std_dev_horz: 0.0_f32,
26448 std_dev_vert: 0.0_f32,
26449 vn: 0.0_f32,
26450 ve: 0.0_f32,
26451 vd: 0.0_f32,
26452 lat_int: 0_i32,
26453 lon_int: 0_i32,
26454 };
26455 #[cfg(feature = "arbitrary")]
26456 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
26457 use arbitrary::{Arbitrary, Unstructured};
26458 let mut buf = [0u8; 1024];
26459 rng.fill_bytes(&mut buf);
26460 let mut unstructured = Unstructured::new(&buf);
26461 Self::arbitrary(&mut unstructured).unwrap_or_default()
26462 }
26463}
26464impl Default for SIM_STATE_DATA {
26465 fn default() -> Self {
26466 Self::DEFAULT.clone()
26467 }
26468}
26469impl MessageData for SIM_STATE_DATA {
26470 type Message = MavMessage;
26471 const ID: u32 = 108u32;
26472 const NAME: &'static str = "SIM_STATE";
26473 const EXTRA_CRC: u8 = 32u8;
26474 const ENCODED_LEN: usize = 92usize;
26475 fn deser(
26476 _version: MavlinkVersion,
26477 __input: &[u8],
26478 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26479 let avail_len = __input.len();
26480 let mut payload_buf = [0; Self::ENCODED_LEN];
26481 let mut buf = if avail_len < Self::ENCODED_LEN {
26482 payload_buf[0..avail_len].copy_from_slice(__input);
26483 Bytes::new(&payload_buf)
26484 } else {
26485 Bytes::new(__input)
26486 };
26487 let mut __struct = Self::default();
26488 __struct.q1 = buf.get_f32_le();
26489 __struct.q2 = buf.get_f32_le();
26490 __struct.q3 = buf.get_f32_le();
26491 __struct.q4 = buf.get_f32_le();
26492 __struct.roll = buf.get_f32_le();
26493 __struct.pitch = buf.get_f32_le();
26494 __struct.yaw = buf.get_f32_le();
26495 __struct.xacc = buf.get_f32_le();
26496 __struct.yacc = buf.get_f32_le();
26497 __struct.zacc = buf.get_f32_le();
26498 __struct.xgyro = buf.get_f32_le();
26499 __struct.ygyro = buf.get_f32_le();
26500 __struct.zgyro = buf.get_f32_le();
26501 __struct.lat = buf.get_f32_le();
26502 __struct.lon = buf.get_f32_le();
26503 __struct.alt = buf.get_f32_le();
26504 __struct.std_dev_horz = buf.get_f32_le();
26505 __struct.std_dev_vert = buf.get_f32_le();
26506 __struct.vn = buf.get_f32_le();
26507 __struct.ve = buf.get_f32_le();
26508 __struct.vd = buf.get_f32_le();
26509 __struct.lat_int = buf.get_i32_le();
26510 __struct.lon_int = buf.get_i32_le();
26511 Ok(__struct)
26512 }
26513 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
26514 let mut __tmp = BytesMut::new(bytes);
26515 #[allow(clippy::absurd_extreme_comparisons)]
26516 #[allow(unused_comparisons)]
26517 if __tmp.remaining() < Self::ENCODED_LEN {
26518 panic!(
26519 "buffer is too small (need {} bytes, but got {})",
26520 Self::ENCODED_LEN,
26521 __tmp.remaining(),
26522 )
26523 }
26524 __tmp.put_f32_le(self.q1);
26525 __tmp.put_f32_le(self.q2);
26526 __tmp.put_f32_le(self.q3);
26527 __tmp.put_f32_le(self.q4);
26528 __tmp.put_f32_le(self.roll);
26529 __tmp.put_f32_le(self.pitch);
26530 __tmp.put_f32_le(self.yaw);
26531 __tmp.put_f32_le(self.xacc);
26532 __tmp.put_f32_le(self.yacc);
26533 __tmp.put_f32_le(self.zacc);
26534 __tmp.put_f32_le(self.xgyro);
26535 __tmp.put_f32_le(self.ygyro);
26536 __tmp.put_f32_le(self.zgyro);
26537 __tmp.put_f32_le(self.lat);
26538 __tmp.put_f32_le(self.lon);
26539 __tmp.put_f32_le(self.alt);
26540 __tmp.put_f32_le(self.std_dev_horz);
26541 __tmp.put_f32_le(self.std_dev_vert);
26542 __tmp.put_f32_le(self.vn);
26543 __tmp.put_f32_le(self.ve);
26544 __tmp.put_f32_le(self.vd);
26545 __tmp.put_i32_le(self.lat_int);
26546 __tmp.put_i32_le(self.lon_int);
26547 if matches!(version, MavlinkVersion::V2) {
26548 let len = __tmp.len();
26549 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
26550 } else {
26551 __tmp.len()
26552 }
26553 }
26554}
26555#[doc = "id: 12904"]
26556#[doc = "Data for filling the OpenDroneID System message. The System Message contains general system information including the operator location/altitude and possible aircraft group and/or category/class information."]
26557#[derive(Debug, Clone, PartialEq)]
26558#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
26559#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
26560pub struct OPEN_DRONE_ID_SYSTEM_DATA {
26561 #[doc = "Latitude of the operator. If unknown: 0 (both Lat/Lon)."]
26562 pub operator_latitude: i32,
26563 #[doc = "Longitude of the operator. If unknown: 0 (both Lat/Lon)."]
26564 pub operator_longitude: i32,
26565 #[doc = "Area Operations Ceiling relative to WGS84. If unknown: -1000 m. Used only for swarms/multiple UA."]
26566 pub area_ceiling: f32,
26567 #[doc = "Area Operations Floor relative to WGS84. If unknown: -1000 m. Used only for swarms/multiple UA."]
26568 pub area_floor: f32,
26569 #[doc = "Geodetic altitude of the operator relative to WGS84. If unknown: -1000 m."]
26570 pub operator_altitude_geo: f32,
26571 #[doc = "32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019."]
26572 pub timestamp: u32,
26573 #[doc = "Number of aircraft in the area, group or formation (default 1). Used only for swarms/multiple UA."]
26574 pub area_count: u16,
26575 #[doc = "Radius of the cylindrical area of the group or formation (default 0). Used only for swarms/multiple UA."]
26576 pub area_radius: u16,
26577 #[doc = "System ID (0 for broadcast)."]
26578 pub target_system: u8,
26579 #[doc = "Component ID (0 for broadcast)."]
26580 pub target_component: u8,
26581 #[doc = "Only used for drone ID data received from other UAs. See detailed description at <https://mavlink.io/en/services/opendroneid.html>."]
26582 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
26583 pub id_or_mac: [u8; 20],
26584 #[doc = "Specifies the operator location type."]
26585 pub operator_location_type: MavOdidOperatorLocationType,
26586 #[doc = "Specifies the classification type of the UA."]
26587 pub classification_type: MavOdidClassificationType,
26588 #[doc = "When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the category of the UA."]
26589 pub category_eu: MavOdidCategoryEu,
26590 #[doc = "When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the class of the UA."]
26591 pub class_eu: MavOdidClassEu,
26592}
26593impl OPEN_DRONE_ID_SYSTEM_DATA {
26594 pub const ENCODED_LEN: usize = 54usize;
26595 pub const DEFAULT: Self = Self {
26596 operator_latitude: 0_i32,
26597 operator_longitude: 0_i32,
26598 area_ceiling: 0.0_f32,
26599 area_floor: 0.0_f32,
26600 operator_altitude_geo: 0.0_f32,
26601 timestamp: 0_u32,
26602 area_count: 0_u16,
26603 area_radius: 0_u16,
26604 target_system: 0_u8,
26605 target_component: 0_u8,
26606 id_or_mac: [0_u8; 20usize],
26607 operator_location_type: MavOdidOperatorLocationType::DEFAULT,
26608 classification_type: MavOdidClassificationType::DEFAULT,
26609 category_eu: MavOdidCategoryEu::DEFAULT,
26610 class_eu: MavOdidClassEu::DEFAULT,
26611 };
26612 #[cfg(feature = "arbitrary")]
26613 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
26614 use arbitrary::{Arbitrary, Unstructured};
26615 let mut buf = [0u8; 1024];
26616 rng.fill_bytes(&mut buf);
26617 let mut unstructured = Unstructured::new(&buf);
26618 Self::arbitrary(&mut unstructured).unwrap_or_default()
26619 }
26620}
26621impl Default for OPEN_DRONE_ID_SYSTEM_DATA {
26622 fn default() -> Self {
26623 Self::DEFAULT.clone()
26624 }
26625}
26626impl MessageData for OPEN_DRONE_ID_SYSTEM_DATA {
26627 type Message = MavMessage;
26628 const ID: u32 = 12904u32;
26629 const NAME: &'static str = "OPEN_DRONE_ID_SYSTEM";
26630 const EXTRA_CRC: u8 = 77u8;
26631 const ENCODED_LEN: usize = 54usize;
26632 fn deser(
26633 _version: MavlinkVersion,
26634 __input: &[u8],
26635 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26636 let avail_len = __input.len();
26637 let mut payload_buf = [0; Self::ENCODED_LEN];
26638 let mut buf = if avail_len < Self::ENCODED_LEN {
26639 payload_buf[0..avail_len].copy_from_slice(__input);
26640 Bytes::new(&payload_buf)
26641 } else {
26642 Bytes::new(__input)
26643 };
26644 let mut __struct = Self::default();
26645 __struct.operator_latitude = buf.get_i32_le();
26646 __struct.operator_longitude = buf.get_i32_le();
26647 __struct.area_ceiling = buf.get_f32_le();
26648 __struct.area_floor = buf.get_f32_le();
26649 __struct.operator_altitude_geo = buf.get_f32_le();
26650 __struct.timestamp = buf.get_u32_le();
26651 __struct.area_count = buf.get_u16_le();
26652 __struct.area_radius = buf.get_u16_le();
26653 __struct.target_system = buf.get_u8();
26654 __struct.target_component = buf.get_u8();
26655 for v in &mut __struct.id_or_mac {
26656 let val = buf.get_u8();
26657 *v = val;
26658 }
26659 let tmp = buf.get_u8();
26660 __struct.operator_location_type =
26661 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
26662 enum_type: "MavOdidOperatorLocationType",
26663 value: tmp as u32,
26664 })?;
26665 let tmp = buf.get_u8();
26666 __struct.classification_type =
26667 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
26668 enum_type: "MavOdidClassificationType",
26669 value: tmp as u32,
26670 })?;
26671 let tmp = buf.get_u8();
26672 __struct.category_eu =
26673 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
26674 enum_type: "MavOdidCategoryEu",
26675 value: tmp as u32,
26676 })?;
26677 let tmp = buf.get_u8();
26678 __struct.class_eu =
26679 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
26680 enum_type: "MavOdidClassEu",
26681 value: tmp as u32,
26682 })?;
26683 Ok(__struct)
26684 }
26685 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
26686 let mut __tmp = BytesMut::new(bytes);
26687 #[allow(clippy::absurd_extreme_comparisons)]
26688 #[allow(unused_comparisons)]
26689 if __tmp.remaining() < Self::ENCODED_LEN {
26690 panic!(
26691 "buffer is too small (need {} bytes, but got {})",
26692 Self::ENCODED_LEN,
26693 __tmp.remaining(),
26694 )
26695 }
26696 __tmp.put_i32_le(self.operator_latitude);
26697 __tmp.put_i32_le(self.operator_longitude);
26698 __tmp.put_f32_le(self.area_ceiling);
26699 __tmp.put_f32_le(self.area_floor);
26700 __tmp.put_f32_le(self.operator_altitude_geo);
26701 __tmp.put_u32_le(self.timestamp);
26702 __tmp.put_u16_le(self.area_count);
26703 __tmp.put_u16_le(self.area_radius);
26704 __tmp.put_u8(self.target_system);
26705 __tmp.put_u8(self.target_component);
26706 for val in &self.id_or_mac {
26707 __tmp.put_u8(*val);
26708 }
26709 __tmp.put_u8(self.operator_location_type as u8);
26710 __tmp.put_u8(self.classification_type as u8);
26711 __tmp.put_u8(self.category_eu as u8);
26712 __tmp.put_u8(self.class_eu as u8);
26713 if matches!(version, MavlinkVersion::V2) {
26714 let len = __tmp.len();
26715 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
26716 } else {
26717 __tmp.len()
26718 }
26719 }
26720}
26721#[doc = "id: 12905"]
26722#[doc = "Data for filling the OpenDroneID Operator ID message, which contains the CAA (Civil Aviation Authority) issued operator ID."]
26723#[derive(Debug, Clone, PartialEq)]
26724#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
26725#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
26726pub struct OPEN_DRONE_ID_OPERATOR_ID_DATA {
26727 #[doc = "System ID (0 for broadcast)."]
26728 pub target_system: u8,
26729 #[doc = "Component ID (0 for broadcast)."]
26730 pub target_component: u8,
26731 #[doc = "Only used for drone ID data received from other UAs. See detailed description at <https://mavlink.io/en/services/opendroneid.html>."]
26732 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
26733 pub id_or_mac: [u8; 20],
26734 #[doc = "Indicates the type of the operator_id field."]
26735 pub operator_id_type: MavOdidOperatorIdType,
26736 #[doc = "Text description or numeric value expressed as ASCII characters. Shall be filled with nulls in the unused portion of the field."]
26737 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
26738 pub operator_id: [u8; 20],
26739}
26740impl OPEN_DRONE_ID_OPERATOR_ID_DATA {
26741 pub const ENCODED_LEN: usize = 43usize;
26742 pub const DEFAULT: Self = Self {
26743 target_system: 0_u8,
26744 target_component: 0_u8,
26745 id_or_mac: [0_u8; 20usize],
26746 operator_id_type: MavOdidOperatorIdType::DEFAULT,
26747 operator_id: [0_u8; 20usize],
26748 };
26749 #[cfg(feature = "arbitrary")]
26750 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
26751 use arbitrary::{Arbitrary, Unstructured};
26752 let mut buf = [0u8; 1024];
26753 rng.fill_bytes(&mut buf);
26754 let mut unstructured = Unstructured::new(&buf);
26755 Self::arbitrary(&mut unstructured).unwrap_or_default()
26756 }
26757}
26758impl Default for OPEN_DRONE_ID_OPERATOR_ID_DATA {
26759 fn default() -> Self {
26760 Self::DEFAULT.clone()
26761 }
26762}
26763impl MessageData for OPEN_DRONE_ID_OPERATOR_ID_DATA {
26764 type Message = MavMessage;
26765 const ID: u32 = 12905u32;
26766 const NAME: &'static str = "OPEN_DRONE_ID_OPERATOR_ID";
26767 const EXTRA_CRC: u8 = 49u8;
26768 const ENCODED_LEN: usize = 43usize;
26769 fn deser(
26770 _version: MavlinkVersion,
26771 __input: &[u8],
26772 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26773 let avail_len = __input.len();
26774 let mut payload_buf = [0; Self::ENCODED_LEN];
26775 let mut buf = if avail_len < Self::ENCODED_LEN {
26776 payload_buf[0..avail_len].copy_from_slice(__input);
26777 Bytes::new(&payload_buf)
26778 } else {
26779 Bytes::new(__input)
26780 };
26781 let mut __struct = Self::default();
26782 __struct.target_system = buf.get_u8();
26783 __struct.target_component = buf.get_u8();
26784 for v in &mut __struct.id_or_mac {
26785 let val = buf.get_u8();
26786 *v = val;
26787 }
26788 let tmp = buf.get_u8();
26789 __struct.operator_id_type =
26790 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
26791 enum_type: "MavOdidOperatorIdType",
26792 value: tmp as u32,
26793 })?;
26794 for v in &mut __struct.operator_id {
26795 let val = buf.get_u8();
26796 *v = val;
26797 }
26798 Ok(__struct)
26799 }
26800 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
26801 let mut __tmp = BytesMut::new(bytes);
26802 #[allow(clippy::absurd_extreme_comparisons)]
26803 #[allow(unused_comparisons)]
26804 if __tmp.remaining() < Self::ENCODED_LEN {
26805 panic!(
26806 "buffer is too small (need {} bytes, but got {})",
26807 Self::ENCODED_LEN,
26808 __tmp.remaining(),
26809 )
26810 }
26811 __tmp.put_u8(self.target_system);
26812 __tmp.put_u8(self.target_component);
26813 for val in &self.id_or_mac {
26814 __tmp.put_u8(*val);
26815 }
26816 __tmp.put_u8(self.operator_id_type as u8);
26817 for val in &self.operator_id {
26818 __tmp.put_u8(*val);
26819 }
26820 if matches!(version, MavlinkVersion::V2) {
26821 let len = __tmp.len();
26822 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
26823 } else {
26824 __tmp.len()
26825 }
26826 }
26827}
26828#[doc = "id: 38"]
26829#[doc = "This message is sent to the MAV to write a partial list. If start index == end index, only one item will be transmitted / updated. If the start index is NOT 0 and above the current list size, this request should be REJECTED!."]
26830#[derive(Debug, Clone, PartialEq)]
26831#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
26832#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
26833pub struct MISSION_WRITE_PARTIAL_LIST_DATA {
26834 #[doc = "Start index. Must be smaller / equal to the largest index of the current onboard list."]
26835 pub start_index: i16,
26836 #[doc = "End index, equal or greater than start index."]
26837 pub end_index: i16,
26838 #[doc = "System ID"]
26839 pub target_system: u8,
26840 #[doc = "Component ID"]
26841 pub target_component: u8,
26842 #[doc = "Mission type."]
26843 #[cfg_attr(feature = "serde", serde(default))]
26844 pub mission_type: MavMissionType,
26845}
26846impl MISSION_WRITE_PARTIAL_LIST_DATA {
26847 pub const ENCODED_LEN: usize = 7usize;
26848 pub const DEFAULT: Self = Self {
26849 start_index: 0_i16,
26850 end_index: 0_i16,
26851 target_system: 0_u8,
26852 target_component: 0_u8,
26853 mission_type: MavMissionType::DEFAULT,
26854 };
26855 #[cfg(feature = "arbitrary")]
26856 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
26857 use arbitrary::{Arbitrary, Unstructured};
26858 let mut buf = [0u8; 1024];
26859 rng.fill_bytes(&mut buf);
26860 let mut unstructured = Unstructured::new(&buf);
26861 Self::arbitrary(&mut unstructured).unwrap_or_default()
26862 }
26863}
26864impl Default for MISSION_WRITE_PARTIAL_LIST_DATA {
26865 fn default() -> Self {
26866 Self::DEFAULT.clone()
26867 }
26868}
26869impl MessageData for MISSION_WRITE_PARTIAL_LIST_DATA {
26870 type Message = MavMessage;
26871 const ID: u32 = 38u32;
26872 const NAME: &'static str = "MISSION_WRITE_PARTIAL_LIST";
26873 const EXTRA_CRC: u8 = 9u8;
26874 const ENCODED_LEN: usize = 7usize;
26875 fn deser(
26876 _version: MavlinkVersion,
26877 __input: &[u8],
26878 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26879 let avail_len = __input.len();
26880 let mut payload_buf = [0; Self::ENCODED_LEN];
26881 let mut buf = if avail_len < Self::ENCODED_LEN {
26882 payload_buf[0..avail_len].copy_from_slice(__input);
26883 Bytes::new(&payload_buf)
26884 } else {
26885 Bytes::new(__input)
26886 };
26887 let mut __struct = Self::default();
26888 __struct.start_index = buf.get_i16_le();
26889 __struct.end_index = buf.get_i16_le();
26890 __struct.target_system = buf.get_u8();
26891 __struct.target_component = buf.get_u8();
26892 let tmp = buf.get_u8();
26893 __struct.mission_type =
26894 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
26895 enum_type: "MavMissionType",
26896 value: tmp as u32,
26897 })?;
26898 Ok(__struct)
26899 }
26900 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
26901 let mut __tmp = BytesMut::new(bytes);
26902 #[allow(clippy::absurd_extreme_comparisons)]
26903 #[allow(unused_comparisons)]
26904 if __tmp.remaining() < Self::ENCODED_LEN {
26905 panic!(
26906 "buffer is too small (need {} bytes, but got {})",
26907 Self::ENCODED_LEN,
26908 __tmp.remaining(),
26909 )
26910 }
26911 __tmp.put_i16_le(self.start_index);
26912 __tmp.put_i16_le(self.end_index);
26913 __tmp.put_u8(self.target_system);
26914 __tmp.put_u8(self.target_component);
26915 __tmp.put_u8(self.mission_type as u8);
26916 if matches!(version, MavlinkVersion::V2) {
26917 let len = __tmp.len();
26918 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
26919 } else {
26920 __tmp.len()
26921 }
26922 }
26923}
26924#[doc = "id: 350"]
26925#[doc = "Large debug/prototyping array. The message uses the maximum available payload for data. The array_id and name fields are used to discriminate between messages in code and in user interfaces (respectively). Do not use in production code."]
26926#[derive(Debug, Clone, PartialEq)]
26927#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
26928#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
26929pub struct DEBUG_FLOAT_ARRAY_DATA {
26930 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
26931 pub time_usec: u64,
26932 #[doc = "Unique ID used to discriminate between arrays"]
26933 pub array_id: u16,
26934 #[doc = "Name, for human-friendly display in a Ground Control Station"]
26935 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
26936 pub name: [u8; 10],
26937 #[doc = "data"]
26938 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
26939 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
26940 pub data: [f32; 58],
26941}
26942impl DEBUG_FLOAT_ARRAY_DATA {
26943 pub const ENCODED_LEN: usize = 252usize;
26944 pub const DEFAULT: Self = Self {
26945 time_usec: 0_u64,
26946 array_id: 0_u16,
26947 name: [0_u8; 10usize],
26948 data: [0.0_f32; 58usize],
26949 };
26950 #[cfg(feature = "arbitrary")]
26951 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
26952 use arbitrary::{Arbitrary, Unstructured};
26953 let mut buf = [0u8; 1024];
26954 rng.fill_bytes(&mut buf);
26955 let mut unstructured = Unstructured::new(&buf);
26956 Self::arbitrary(&mut unstructured).unwrap_or_default()
26957 }
26958}
26959impl Default for DEBUG_FLOAT_ARRAY_DATA {
26960 fn default() -> Self {
26961 Self::DEFAULT.clone()
26962 }
26963}
26964impl MessageData for DEBUG_FLOAT_ARRAY_DATA {
26965 type Message = MavMessage;
26966 const ID: u32 = 350u32;
26967 const NAME: &'static str = "DEBUG_FLOAT_ARRAY";
26968 const EXTRA_CRC: u8 = 232u8;
26969 const ENCODED_LEN: usize = 252usize;
26970 fn deser(
26971 _version: MavlinkVersion,
26972 __input: &[u8],
26973 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26974 let avail_len = __input.len();
26975 let mut payload_buf = [0; Self::ENCODED_LEN];
26976 let mut buf = if avail_len < Self::ENCODED_LEN {
26977 payload_buf[0..avail_len].copy_from_slice(__input);
26978 Bytes::new(&payload_buf)
26979 } else {
26980 Bytes::new(__input)
26981 };
26982 let mut __struct = Self::default();
26983 __struct.time_usec = buf.get_u64_le();
26984 __struct.array_id = buf.get_u16_le();
26985 for v in &mut __struct.name {
26986 let val = buf.get_u8();
26987 *v = val;
26988 }
26989 for v in &mut __struct.data {
26990 let val = buf.get_f32_le();
26991 *v = val;
26992 }
26993 Ok(__struct)
26994 }
26995 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
26996 let mut __tmp = BytesMut::new(bytes);
26997 #[allow(clippy::absurd_extreme_comparisons)]
26998 #[allow(unused_comparisons)]
26999 if __tmp.remaining() < Self::ENCODED_LEN {
27000 panic!(
27001 "buffer is too small (need {} bytes, but got {})",
27002 Self::ENCODED_LEN,
27003 __tmp.remaining(),
27004 )
27005 }
27006 __tmp.put_u64_le(self.time_usec);
27007 __tmp.put_u16_le(self.array_id);
27008 for val in &self.name {
27009 __tmp.put_u8(*val);
27010 }
27011 for val in &self.data {
27012 __tmp.put_f32_le(*val);
27013 }
27014 if matches!(version, MavlinkVersion::V2) {
27015 let len = __tmp.len();
27016 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27017 } else {
27018 __tmp.len()
27019 }
27020 }
27021}
27022#[doc = "id: 288"]
27023#[doc = "High level message to control a gimbal manually. The angles or angular rates are unitless; the actual rates will depend on internal gimbal manager settings/configuration (e.g. set by parameters). This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case."]
27024#[derive(Debug, Clone, PartialEq)]
27025#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27026#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27027pub struct GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA {
27028 #[doc = "High level gimbal manager flags."]
27029 pub flags: GimbalManagerFlags,
27030 #[doc = "Pitch angle unitless (-1..1, positive: up, negative: down, NaN to be ignored)."]
27031 pub pitch: f32,
27032 #[doc = "Yaw angle unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored)."]
27033 pub yaw: f32,
27034 #[doc = "Pitch angular rate unitless (-1..1, positive: up, negative: down, NaN to be ignored)."]
27035 pub pitch_rate: f32,
27036 #[doc = "Yaw angular rate unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored)."]
27037 pub yaw_rate: f32,
27038 #[doc = "System ID"]
27039 pub target_system: u8,
27040 #[doc = "Component ID"]
27041 pub target_component: u8,
27042 #[doc = "Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals)."]
27043 pub gimbal_device_id: u8,
27044}
27045impl GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA {
27046 pub const ENCODED_LEN: usize = 23usize;
27047 pub const DEFAULT: Self = Self {
27048 flags: GimbalManagerFlags::DEFAULT,
27049 pitch: 0.0_f32,
27050 yaw: 0.0_f32,
27051 pitch_rate: 0.0_f32,
27052 yaw_rate: 0.0_f32,
27053 target_system: 0_u8,
27054 target_component: 0_u8,
27055 gimbal_device_id: 0_u8,
27056 };
27057 #[cfg(feature = "arbitrary")]
27058 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27059 use arbitrary::{Arbitrary, Unstructured};
27060 let mut buf = [0u8; 1024];
27061 rng.fill_bytes(&mut buf);
27062 let mut unstructured = Unstructured::new(&buf);
27063 Self::arbitrary(&mut unstructured).unwrap_or_default()
27064 }
27065}
27066impl Default for GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA {
27067 fn default() -> Self {
27068 Self::DEFAULT.clone()
27069 }
27070}
27071impl MessageData for GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA {
27072 type Message = MavMessage;
27073 const ID: u32 = 288u32;
27074 const NAME: &'static str = "GIMBAL_MANAGER_SET_MANUAL_CONTROL";
27075 const EXTRA_CRC: u8 = 20u8;
27076 const ENCODED_LEN: usize = 23usize;
27077 fn deser(
27078 _version: MavlinkVersion,
27079 __input: &[u8],
27080 ) -> Result<Self, ::mavlink_core::error::ParserError> {
27081 let avail_len = __input.len();
27082 let mut payload_buf = [0; Self::ENCODED_LEN];
27083 let mut buf = if avail_len < Self::ENCODED_LEN {
27084 payload_buf[0..avail_len].copy_from_slice(__input);
27085 Bytes::new(&payload_buf)
27086 } else {
27087 Bytes::new(__input)
27088 };
27089 let mut __struct = Self::default();
27090 let tmp = buf.get_u32_le();
27091 __struct.flags = GimbalManagerFlags::from_bits(tmp & GimbalManagerFlags::all().bits())
27092 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
27093 flag_type: "GimbalManagerFlags",
27094 value: tmp as u32,
27095 })?;
27096 __struct.pitch = buf.get_f32_le();
27097 __struct.yaw = buf.get_f32_le();
27098 __struct.pitch_rate = buf.get_f32_le();
27099 __struct.yaw_rate = buf.get_f32_le();
27100 __struct.target_system = buf.get_u8();
27101 __struct.target_component = buf.get_u8();
27102 __struct.gimbal_device_id = buf.get_u8();
27103 Ok(__struct)
27104 }
27105 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27106 let mut __tmp = BytesMut::new(bytes);
27107 #[allow(clippy::absurd_extreme_comparisons)]
27108 #[allow(unused_comparisons)]
27109 if __tmp.remaining() < Self::ENCODED_LEN {
27110 panic!(
27111 "buffer is too small (need {} bytes, but got {})",
27112 Self::ENCODED_LEN,
27113 __tmp.remaining(),
27114 )
27115 }
27116 __tmp.put_u32_le(self.flags.bits());
27117 __tmp.put_f32_le(self.pitch);
27118 __tmp.put_f32_le(self.yaw);
27119 __tmp.put_f32_le(self.pitch_rate);
27120 __tmp.put_f32_le(self.yaw_rate);
27121 __tmp.put_u8(self.target_system);
27122 __tmp.put_u8(self.target_component);
27123 __tmp.put_u8(self.gimbal_device_id);
27124 if matches!(version, MavlinkVersion::V2) {
27125 let len = __tmp.len();
27126 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27127 } else {
27128 __tmp.len()
27129 }
27130 }
27131}
27132#[doc = "id: 4"]
27133#[doc = "A ping message either requesting or responding to a ping. This allows to measure the system latencies, including serial port, radio modem and UDP connections. The ping microservice is documented at <https://mavlink.io/en/services/ping.html>."]
27134#[derive(Debug, Clone, PartialEq)]
27135#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27136#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27137pub struct PING_DATA {
27138 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
27139 pub time_usec: u64,
27140 #[doc = "PING sequence"]
27141 pub seq: u32,
27142 #[doc = "0: request ping from all receiving systems. If greater than 0: message is a ping response and number is the system id of the requesting system"]
27143 pub target_system: u8,
27144 #[doc = "0: request ping from all receiving components. If greater than 0: message is a ping response and number is the component id of the requesting component."]
27145 pub target_component: u8,
27146}
27147impl PING_DATA {
27148 pub const ENCODED_LEN: usize = 14usize;
27149 pub const DEFAULT: Self = Self {
27150 time_usec: 0_u64,
27151 seq: 0_u32,
27152 target_system: 0_u8,
27153 target_component: 0_u8,
27154 };
27155 #[cfg(feature = "arbitrary")]
27156 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27157 use arbitrary::{Arbitrary, Unstructured};
27158 let mut buf = [0u8; 1024];
27159 rng.fill_bytes(&mut buf);
27160 let mut unstructured = Unstructured::new(&buf);
27161 Self::arbitrary(&mut unstructured).unwrap_or_default()
27162 }
27163}
27164impl Default for PING_DATA {
27165 fn default() -> Self {
27166 Self::DEFAULT.clone()
27167 }
27168}
27169impl MessageData for PING_DATA {
27170 type Message = MavMessage;
27171 const ID: u32 = 4u32;
27172 const NAME: &'static str = "PING";
27173 const EXTRA_CRC: u8 = 237u8;
27174 const ENCODED_LEN: usize = 14usize;
27175 fn deser(
27176 _version: MavlinkVersion,
27177 __input: &[u8],
27178 ) -> Result<Self, ::mavlink_core::error::ParserError> {
27179 let avail_len = __input.len();
27180 let mut payload_buf = [0; Self::ENCODED_LEN];
27181 let mut buf = if avail_len < Self::ENCODED_LEN {
27182 payload_buf[0..avail_len].copy_from_slice(__input);
27183 Bytes::new(&payload_buf)
27184 } else {
27185 Bytes::new(__input)
27186 };
27187 let mut __struct = Self::default();
27188 __struct.time_usec = buf.get_u64_le();
27189 __struct.seq = buf.get_u32_le();
27190 __struct.target_system = buf.get_u8();
27191 __struct.target_component = buf.get_u8();
27192 Ok(__struct)
27193 }
27194 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27195 let mut __tmp = BytesMut::new(bytes);
27196 #[allow(clippy::absurd_extreme_comparisons)]
27197 #[allow(unused_comparisons)]
27198 if __tmp.remaining() < Self::ENCODED_LEN {
27199 panic!(
27200 "buffer is too small (need {} bytes, but got {})",
27201 Self::ENCODED_LEN,
27202 __tmp.remaining(),
27203 )
27204 }
27205 __tmp.put_u64_le(self.time_usec);
27206 __tmp.put_u32_le(self.seq);
27207 __tmp.put_u8(self.target_system);
27208 __tmp.put_u8(self.target_component);
27209 if matches!(version, MavlinkVersion::V2) {
27210 let len = __tmp.len();
27211 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27212 } else {
27213 __tmp.len()
27214 }
27215 }
27216}
27217#[doc = "id: 260"]
27218#[doc = "Settings of a camera. Can be requested with a MAV_CMD_REQUEST_MESSAGE command."]
27219#[derive(Debug, Clone, PartialEq)]
27220#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27221#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27222pub struct CAMERA_SETTINGS_DATA {
27223 #[doc = "Timestamp (time since system boot)."]
27224 pub time_boot_ms: u32,
27225 #[doc = "Camera mode"]
27226 pub mode_id: CameraMode,
27227 #[doc = "Current zoom level as a percentage of the full range (0.0 to 100.0, NaN if not known)"]
27228 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
27229 pub zoomLevel: f32,
27230 #[doc = "Current focus level as a percentage of the full range (0.0 to 100.0, NaN if not known)"]
27231 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
27232 pub focusLevel: f32,
27233 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
27234 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
27235 pub camera_device_id: u8,
27236}
27237impl CAMERA_SETTINGS_DATA {
27238 pub const ENCODED_LEN: usize = 14usize;
27239 pub const DEFAULT: Self = Self {
27240 time_boot_ms: 0_u32,
27241 mode_id: CameraMode::DEFAULT,
27242 zoomLevel: 0.0_f32,
27243 focusLevel: 0.0_f32,
27244 camera_device_id: 0_u8,
27245 };
27246 #[cfg(feature = "arbitrary")]
27247 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27248 use arbitrary::{Arbitrary, Unstructured};
27249 let mut buf = [0u8; 1024];
27250 rng.fill_bytes(&mut buf);
27251 let mut unstructured = Unstructured::new(&buf);
27252 Self::arbitrary(&mut unstructured).unwrap_or_default()
27253 }
27254}
27255impl Default for CAMERA_SETTINGS_DATA {
27256 fn default() -> Self {
27257 Self::DEFAULT.clone()
27258 }
27259}
27260impl MessageData for CAMERA_SETTINGS_DATA {
27261 type Message = MavMessage;
27262 const ID: u32 = 260u32;
27263 const NAME: &'static str = "CAMERA_SETTINGS";
27264 const EXTRA_CRC: u8 = 146u8;
27265 const ENCODED_LEN: usize = 14usize;
27266 fn deser(
27267 _version: MavlinkVersion,
27268 __input: &[u8],
27269 ) -> Result<Self, ::mavlink_core::error::ParserError> {
27270 let avail_len = __input.len();
27271 let mut payload_buf = [0; Self::ENCODED_LEN];
27272 let mut buf = if avail_len < Self::ENCODED_LEN {
27273 payload_buf[0..avail_len].copy_from_slice(__input);
27274 Bytes::new(&payload_buf)
27275 } else {
27276 Bytes::new(__input)
27277 };
27278 let mut __struct = Self::default();
27279 __struct.time_boot_ms = buf.get_u32_le();
27280 let tmp = buf.get_u8();
27281 __struct.mode_id =
27282 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
27283 enum_type: "CameraMode",
27284 value: tmp as u32,
27285 })?;
27286 __struct.zoomLevel = buf.get_f32_le();
27287 __struct.focusLevel = buf.get_f32_le();
27288 __struct.camera_device_id = buf.get_u8();
27289 Ok(__struct)
27290 }
27291 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27292 let mut __tmp = BytesMut::new(bytes);
27293 #[allow(clippy::absurd_extreme_comparisons)]
27294 #[allow(unused_comparisons)]
27295 if __tmp.remaining() < Self::ENCODED_LEN {
27296 panic!(
27297 "buffer is too small (need {} bytes, but got {})",
27298 Self::ENCODED_LEN,
27299 __tmp.remaining(),
27300 )
27301 }
27302 __tmp.put_u32_le(self.time_boot_ms);
27303 __tmp.put_u8(self.mode_id as u8);
27304 __tmp.put_f32_le(self.zoomLevel);
27305 __tmp.put_f32_le(self.focusLevel);
27306 __tmp.put_u8(self.camera_device_id);
27307 if matches!(version, MavlinkVersion::V2) {
27308 let len = __tmp.len();
27309 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27310 } else {
27311 __tmp.len()
27312 }
27313 }
27314}
27315#[doc = "id: 133"]
27316#[doc = "Request for terrain data and terrain status. See terrain protocol docs: <https://mavlink.io/en/services/terrain.html>."]
27317#[derive(Debug, Clone, PartialEq)]
27318#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27319#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27320pub struct TERRAIN_REQUEST_DATA {
27321 #[doc = "Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits)"]
27322 pub mask: u64,
27323 #[doc = "Latitude of SW corner of first grid"]
27324 pub lat: i32,
27325 #[doc = "Longitude of SW corner of first grid"]
27326 pub lon: i32,
27327 #[doc = "Grid spacing"]
27328 pub grid_spacing: u16,
27329}
27330impl TERRAIN_REQUEST_DATA {
27331 pub const ENCODED_LEN: usize = 18usize;
27332 pub const DEFAULT: Self = Self {
27333 mask: 0_u64,
27334 lat: 0_i32,
27335 lon: 0_i32,
27336 grid_spacing: 0_u16,
27337 };
27338 #[cfg(feature = "arbitrary")]
27339 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27340 use arbitrary::{Arbitrary, Unstructured};
27341 let mut buf = [0u8; 1024];
27342 rng.fill_bytes(&mut buf);
27343 let mut unstructured = Unstructured::new(&buf);
27344 Self::arbitrary(&mut unstructured).unwrap_or_default()
27345 }
27346}
27347impl Default for TERRAIN_REQUEST_DATA {
27348 fn default() -> Self {
27349 Self::DEFAULT.clone()
27350 }
27351}
27352impl MessageData for TERRAIN_REQUEST_DATA {
27353 type Message = MavMessage;
27354 const ID: u32 = 133u32;
27355 const NAME: &'static str = "TERRAIN_REQUEST";
27356 const EXTRA_CRC: u8 = 6u8;
27357 const ENCODED_LEN: usize = 18usize;
27358 fn deser(
27359 _version: MavlinkVersion,
27360 __input: &[u8],
27361 ) -> Result<Self, ::mavlink_core::error::ParserError> {
27362 let avail_len = __input.len();
27363 let mut payload_buf = [0; Self::ENCODED_LEN];
27364 let mut buf = if avail_len < Self::ENCODED_LEN {
27365 payload_buf[0..avail_len].copy_from_slice(__input);
27366 Bytes::new(&payload_buf)
27367 } else {
27368 Bytes::new(__input)
27369 };
27370 let mut __struct = Self::default();
27371 __struct.mask = buf.get_u64_le();
27372 __struct.lat = buf.get_i32_le();
27373 __struct.lon = buf.get_i32_le();
27374 __struct.grid_spacing = buf.get_u16_le();
27375 Ok(__struct)
27376 }
27377 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27378 let mut __tmp = BytesMut::new(bytes);
27379 #[allow(clippy::absurd_extreme_comparisons)]
27380 #[allow(unused_comparisons)]
27381 if __tmp.remaining() < Self::ENCODED_LEN {
27382 panic!(
27383 "buffer is too small (need {} bytes, but got {})",
27384 Self::ENCODED_LEN,
27385 __tmp.remaining(),
27386 )
27387 }
27388 __tmp.put_u64_le(self.mask);
27389 __tmp.put_i32_le(self.lat);
27390 __tmp.put_i32_le(self.lon);
27391 __tmp.put_u16_le(self.grid_spacing);
27392 if matches!(version, MavlinkVersion::V2) {
27393 let len = __tmp.len();
27394 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27395 } else {
27396 __tmp.len()
27397 }
27398 }
27399}
27400#[doc = "id: 284"]
27401#[doc = "Low level message to control a gimbal device's attitude. \t This message is to be sent from the gimbal manager to the gimbal device component. \t The quaternion and angular velocities can be set to NaN according to use case. \t For the angles encoded in the quaternion and the angular velocities holds: \t If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME is set, then they are relative to the vehicle heading (vehicle frame). \t If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is set, then they are relative to absolute North (earth frame). \t If neither of these flags are set, then (for backwards compatibility) it holds: \t If the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, then they are relative to absolute North (earth frame), \t else they are relative to the vehicle heading (vehicle frame). \t Setting both GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME and GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is not allowed. \t These rules are to ensure backwards compatibility. \t New implementations should always set either GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME or GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME."]
27402#[derive(Debug, Clone, PartialEq)]
27403#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27404#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27405pub struct GIMBAL_DEVICE_SET_ATTITUDE_DATA {
27406 #[doc = "Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). The frame is described in the message description. Set fields to NaN to be ignored."]
27407 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
27408 pub q: [f32; 4],
27409 #[doc = "X component of angular velocity (positive: rolling to the right). The frame is described in the message description. NaN to be ignored."]
27410 pub angular_velocity_x: f32,
27411 #[doc = "Y component of angular velocity (positive: pitching up). The frame is described in the message description. NaN to be ignored."]
27412 pub angular_velocity_y: f32,
27413 #[doc = "Z component of angular velocity (positive: yawing to the right). The frame is described in the message description. NaN to be ignored."]
27414 pub angular_velocity_z: f32,
27415 #[doc = "Low level gimbal flags."]
27416 pub flags: GimbalDeviceFlags,
27417 #[doc = "System ID"]
27418 pub target_system: u8,
27419 #[doc = "Component ID"]
27420 pub target_component: u8,
27421}
27422impl GIMBAL_DEVICE_SET_ATTITUDE_DATA {
27423 pub const ENCODED_LEN: usize = 32usize;
27424 pub const DEFAULT: Self = Self {
27425 q: [0.0_f32; 4usize],
27426 angular_velocity_x: 0.0_f32,
27427 angular_velocity_y: 0.0_f32,
27428 angular_velocity_z: 0.0_f32,
27429 flags: GimbalDeviceFlags::DEFAULT,
27430 target_system: 0_u8,
27431 target_component: 0_u8,
27432 };
27433 #[cfg(feature = "arbitrary")]
27434 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27435 use arbitrary::{Arbitrary, Unstructured};
27436 let mut buf = [0u8; 1024];
27437 rng.fill_bytes(&mut buf);
27438 let mut unstructured = Unstructured::new(&buf);
27439 Self::arbitrary(&mut unstructured).unwrap_or_default()
27440 }
27441}
27442impl Default for GIMBAL_DEVICE_SET_ATTITUDE_DATA {
27443 fn default() -> Self {
27444 Self::DEFAULT.clone()
27445 }
27446}
27447impl MessageData for GIMBAL_DEVICE_SET_ATTITUDE_DATA {
27448 type Message = MavMessage;
27449 const ID: u32 = 284u32;
27450 const NAME: &'static str = "GIMBAL_DEVICE_SET_ATTITUDE";
27451 const EXTRA_CRC: u8 = 99u8;
27452 const ENCODED_LEN: usize = 32usize;
27453 fn deser(
27454 _version: MavlinkVersion,
27455 __input: &[u8],
27456 ) -> Result<Self, ::mavlink_core::error::ParserError> {
27457 let avail_len = __input.len();
27458 let mut payload_buf = [0; Self::ENCODED_LEN];
27459 let mut buf = if avail_len < Self::ENCODED_LEN {
27460 payload_buf[0..avail_len].copy_from_slice(__input);
27461 Bytes::new(&payload_buf)
27462 } else {
27463 Bytes::new(__input)
27464 };
27465 let mut __struct = Self::default();
27466 for v in &mut __struct.q {
27467 let val = buf.get_f32_le();
27468 *v = val;
27469 }
27470 __struct.angular_velocity_x = buf.get_f32_le();
27471 __struct.angular_velocity_y = buf.get_f32_le();
27472 __struct.angular_velocity_z = buf.get_f32_le();
27473 let tmp = buf.get_u16_le();
27474 __struct.flags = GimbalDeviceFlags::from_bits(tmp & GimbalDeviceFlags::all().bits())
27475 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
27476 flag_type: "GimbalDeviceFlags",
27477 value: tmp as u32,
27478 })?;
27479 __struct.target_system = buf.get_u8();
27480 __struct.target_component = buf.get_u8();
27481 Ok(__struct)
27482 }
27483 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27484 let mut __tmp = BytesMut::new(bytes);
27485 #[allow(clippy::absurd_extreme_comparisons)]
27486 #[allow(unused_comparisons)]
27487 if __tmp.remaining() < Self::ENCODED_LEN {
27488 panic!(
27489 "buffer is too small (need {} bytes, but got {})",
27490 Self::ENCODED_LEN,
27491 __tmp.remaining(),
27492 )
27493 }
27494 for val in &self.q {
27495 __tmp.put_f32_le(*val);
27496 }
27497 __tmp.put_f32_le(self.angular_velocity_x);
27498 __tmp.put_f32_le(self.angular_velocity_y);
27499 __tmp.put_f32_le(self.angular_velocity_z);
27500 __tmp.put_u16_le(self.flags.bits());
27501 __tmp.put_u8(self.target_system);
27502 __tmp.put_u8(self.target_component);
27503 if matches!(version, MavlinkVersion::V2) {
27504 let len = __tmp.len();
27505 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27506 } else {
27507 __tmp.len()
27508 }
27509 }
27510}
27511#[doc = "id: 138"]
27512#[doc = "Motion capture attitude and position."]
27513#[derive(Debug, Clone, PartialEq)]
27514#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27515#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27516pub struct ATT_POS_MOCAP_DATA {
27517 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
27518 pub time_usec: u64,
27519 #[doc = "Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)"]
27520 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
27521 pub q: [f32; 4],
27522 #[doc = "X position (NED)"]
27523 pub x: f32,
27524 #[doc = "Y position (NED)"]
27525 pub y: f32,
27526 #[doc = "Z position (NED)"]
27527 pub z: f32,
27528 #[doc = "Row-major representation of a pose 6x6 cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array."]
27529 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
27530 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
27531 pub covariance: [f32; 21],
27532}
27533impl ATT_POS_MOCAP_DATA {
27534 pub const ENCODED_LEN: usize = 120usize;
27535 pub const DEFAULT: Self = Self {
27536 time_usec: 0_u64,
27537 q: [0.0_f32; 4usize],
27538 x: 0.0_f32,
27539 y: 0.0_f32,
27540 z: 0.0_f32,
27541 covariance: [0.0_f32; 21usize],
27542 };
27543 #[cfg(feature = "arbitrary")]
27544 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27545 use arbitrary::{Arbitrary, Unstructured};
27546 let mut buf = [0u8; 1024];
27547 rng.fill_bytes(&mut buf);
27548 let mut unstructured = Unstructured::new(&buf);
27549 Self::arbitrary(&mut unstructured).unwrap_or_default()
27550 }
27551}
27552impl Default for ATT_POS_MOCAP_DATA {
27553 fn default() -> Self {
27554 Self::DEFAULT.clone()
27555 }
27556}
27557impl MessageData for ATT_POS_MOCAP_DATA {
27558 type Message = MavMessage;
27559 const ID: u32 = 138u32;
27560 const NAME: &'static str = "ATT_POS_MOCAP";
27561 const EXTRA_CRC: u8 = 109u8;
27562 const ENCODED_LEN: usize = 120usize;
27563 fn deser(
27564 _version: MavlinkVersion,
27565 __input: &[u8],
27566 ) -> Result<Self, ::mavlink_core::error::ParserError> {
27567 let avail_len = __input.len();
27568 let mut payload_buf = [0; Self::ENCODED_LEN];
27569 let mut buf = if avail_len < Self::ENCODED_LEN {
27570 payload_buf[0..avail_len].copy_from_slice(__input);
27571 Bytes::new(&payload_buf)
27572 } else {
27573 Bytes::new(__input)
27574 };
27575 let mut __struct = Self::default();
27576 __struct.time_usec = buf.get_u64_le();
27577 for v in &mut __struct.q {
27578 let val = buf.get_f32_le();
27579 *v = val;
27580 }
27581 __struct.x = buf.get_f32_le();
27582 __struct.y = buf.get_f32_le();
27583 __struct.z = buf.get_f32_le();
27584 for v in &mut __struct.covariance {
27585 let val = buf.get_f32_le();
27586 *v = val;
27587 }
27588 Ok(__struct)
27589 }
27590 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27591 let mut __tmp = BytesMut::new(bytes);
27592 #[allow(clippy::absurd_extreme_comparisons)]
27593 #[allow(unused_comparisons)]
27594 if __tmp.remaining() < Self::ENCODED_LEN {
27595 panic!(
27596 "buffer is too small (need {} bytes, but got {})",
27597 Self::ENCODED_LEN,
27598 __tmp.remaining(),
27599 )
27600 }
27601 __tmp.put_u64_le(self.time_usec);
27602 for val in &self.q {
27603 __tmp.put_f32_le(*val);
27604 }
27605 __tmp.put_f32_le(self.x);
27606 __tmp.put_f32_le(self.y);
27607 __tmp.put_f32_le(self.z);
27608 for val in &self.covariance {
27609 __tmp.put_f32_le(*val);
27610 }
27611 if matches!(version, MavlinkVersion::V2) {
27612 let len = __tmp.len();
27613 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27614 } else {
27615 __tmp.len()
27616 }
27617 }
27618}
27619#[doc = "id: 0"]
27620#[doc = "The heartbeat message shows that a system or component is present and responding. The type and autopilot fields (along with the message component id), allow the receiving system to treat further messages from this system appropriately (e.g. by laying out the user interface based on the autopilot). This microservice is documented at <https://mavlink.io/en/services/heartbeat.html>."]
27621#[derive(Debug, Clone, PartialEq)]
27622#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27623#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27624pub struct HEARTBEAT_DATA {
27625 #[doc = "A bitfield for use for autopilot-specific flags"]
27626 pub custom_mode: u32,
27627 #[doc = "Vehicle or component type. For a flight controller component the vehicle type (quadrotor, helicopter, etc.). For other components the component type (e.g. camera, gimbal, etc.). This should be used in preference to component id for identifying the component type."]
27628 pub mavtype: MavType,
27629 #[doc = "Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers."]
27630 pub autopilot: MavAutopilot,
27631 #[doc = "System mode bitmap."]
27632 pub base_mode: MavModeFlag,
27633 #[doc = "System status flag."]
27634 pub system_status: MavState,
27635 #[doc = "MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version"]
27636 pub mavlink_version: u8,
27637}
27638impl HEARTBEAT_DATA {
27639 pub const ENCODED_LEN: usize = 9usize;
27640 pub const DEFAULT: Self = Self {
27641 custom_mode: 0_u32,
27642 mavtype: MavType::DEFAULT,
27643 autopilot: MavAutopilot::DEFAULT,
27644 base_mode: MavModeFlag::DEFAULT,
27645 system_status: MavState::DEFAULT,
27646 mavlink_version: 0_u8,
27647 };
27648 #[cfg(feature = "arbitrary")]
27649 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27650 use arbitrary::{Arbitrary, Unstructured};
27651 let mut buf = [0u8; 1024];
27652 rng.fill_bytes(&mut buf);
27653 let mut unstructured = Unstructured::new(&buf);
27654 Self::arbitrary(&mut unstructured).unwrap_or_default()
27655 }
27656}
27657impl Default for HEARTBEAT_DATA {
27658 fn default() -> Self {
27659 Self::DEFAULT.clone()
27660 }
27661}
27662impl MessageData for HEARTBEAT_DATA {
27663 type Message = MavMessage;
27664 const ID: u32 = 0u32;
27665 const NAME: &'static str = "HEARTBEAT";
27666 const EXTRA_CRC: u8 = 50u8;
27667 const ENCODED_LEN: usize = 9usize;
27668 fn deser(
27669 _version: MavlinkVersion,
27670 __input: &[u8],
27671 ) -> Result<Self, ::mavlink_core::error::ParserError> {
27672 let avail_len = __input.len();
27673 let mut payload_buf = [0; Self::ENCODED_LEN];
27674 let mut buf = if avail_len < Self::ENCODED_LEN {
27675 payload_buf[0..avail_len].copy_from_slice(__input);
27676 Bytes::new(&payload_buf)
27677 } else {
27678 Bytes::new(__input)
27679 };
27680 let mut __struct = Self::default();
27681 __struct.custom_mode = buf.get_u32_le();
27682 let tmp = buf.get_u8();
27683 __struct.mavtype =
27684 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
27685 enum_type: "MavType",
27686 value: tmp as u32,
27687 })?;
27688 let tmp = buf.get_u8();
27689 __struct.autopilot =
27690 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
27691 enum_type: "MavAutopilot",
27692 value: tmp as u32,
27693 })?;
27694 let tmp = buf.get_u8();
27695 __struct.base_mode = MavModeFlag::from_bits(tmp & MavModeFlag::all().bits()).ok_or(
27696 ::mavlink_core::error::ParserError::InvalidFlag {
27697 flag_type: "MavModeFlag",
27698 value: tmp as u32,
27699 },
27700 )?;
27701 let tmp = buf.get_u8();
27702 __struct.system_status =
27703 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
27704 enum_type: "MavState",
27705 value: tmp as u32,
27706 })?;
27707 __struct.mavlink_version = buf.get_u8();
27708 Ok(__struct)
27709 }
27710 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27711 let mut __tmp = BytesMut::new(bytes);
27712 #[allow(clippy::absurd_extreme_comparisons)]
27713 #[allow(unused_comparisons)]
27714 if __tmp.remaining() < Self::ENCODED_LEN {
27715 panic!(
27716 "buffer is too small (need {} bytes, but got {})",
27717 Self::ENCODED_LEN,
27718 __tmp.remaining(),
27719 )
27720 }
27721 __tmp.put_u32_le(self.custom_mode);
27722 __tmp.put_u8(self.mavtype as u8);
27723 __tmp.put_u8(self.autopilot as u8);
27724 __tmp.put_u8(self.base_mode.bits());
27725 __tmp.put_u8(self.system_status as u8);
27726 __tmp.put_u8(self.mavlink_version);
27727 if matches!(version, MavlinkVersion::V2) {
27728 let len = __tmp.len();
27729 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27730 } else {
27731 __tmp.len()
27732 }
27733 }
27734}
27735#[doc = "id: 330"]
27736#[doc = "Obstacle distances in front of the sensor, starting from the left in increment degrees to the right."]
27737#[derive(Debug, Clone, PartialEq)]
27738#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27739#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27740pub struct OBSTACLE_DISTANCE_DATA {
27741 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
27742 pub time_usec: u64,
27743 #[doc = "Distance of obstacles around the vehicle with index 0 corresponding to north + angle_offset, unless otherwise specified in the frame. A value of 0 is valid and means that the obstacle is practically touching the sensor. A value of max_distance +1 means no obstacle is present. A value of UINT16_MAX for unknown/not used. In a array element, one unit corresponds to 1cm."]
27744 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
27745 pub distances: [u16; 72],
27746 #[doc = "Minimum distance the sensor can measure."]
27747 pub min_distance: u16,
27748 #[doc = "Maximum distance the sensor can measure."]
27749 pub max_distance: u16,
27750 #[doc = "Class id of the distance sensor type."]
27751 pub sensor_type: MavDistanceSensor,
27752 #[doc = "Angular width in degrees of each array element. Increment direction is clockwise. This field is ignored if increment_f is non-zero."]
27753 pub increment: u8,
27754 #[doc = "Angular width in degrees of each array element as a float. If non-zero then this value is used instead of the uint8_t increment field. Positive is clockwise direction, negative is counter-clockwise."]
27755 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
27756 pub increment_f: f32,
27757 #[doc = "Relative angle offset of the 0-index element in the distances array. Value of 0 corresponds to forward. Positive is clockwise direction, negative is counter-clockwise."]
27758 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
27759 pub angle_offset: f32,
27760 #[doc = "Coordinate frame of reference for the yaw rotation and offset of the sensor data. Defaults to MAV_FRAME_GLOBAL, which is north aligned. For body-mounted sensors use MAV_FRAME_BODY_FRD, which is vehicle front aligned."]
27761 #[cfg_attr(feature = "serde", serde(default))]
27762 pub frame: MavFrame,
27763}
27764impl OBSTACLE_DISTANCE_DATA {
27765 pub const ENCODED_LEN: usize = 167usize;
27766 pub const DEFAULT: Self = Self {
27767 time_usec: 0_u64,
27768 distances: [0_u16; 72usize],
27769 min_distance: 0_u16,
27770 max_distance: 0_u16,
27771 sensor_type: MavDistanceSensor::DEFAULT,
27772 increment: 0_u8,
27773 increment_f: 0.0_f32,
27774 angle_offset: 0.0_f32,
27775 frame: MavFrame::DEFAULT,
27776 };
27777 #[cfg(feature = "arbitrary")]
27778 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27779 use arbitrary::{Arbitrary, Unstructured};
27780 let mut buf = [0u8; 1024];
27781 rng.fill_bytes(&mut buf);
27782 let mut unstructured = Unstructured::new(&buf);
27783 Self::arbitrary(&mut unstructured).unwrap_or_default()
27784 }
27785}
27786impl Default for OBSTACLE_DISTANCE_DATA {
27787 fn default() -> Self {
27788 Self::DEFAULT.clone()
27789 }
27790}
27791impl MessageData for OBSTACLE_DISTANCE_DATA {
27792 type Message = MavMessage;
27793 const ID: u32 = 330u32;
27794 const NAME: &'static str = "OBSTACLE_DISTANCE";
27795 const EXTRA_CRC: u8 = 23u8;
27796 const ENCODED_LEN: usize = 167usize;
27797 fn deser(
27798 _version: MavlinkVersion,
27799 __input: &[u8],
27800 ) -> Result<Self, ::mavlink_core::error::ParserError> {
27801 let avail_len = __input.len();
27802 let mut payload_buf = [0; Self::ENCODED_LEN];
27803 let mut buf = if avail_len < Self::ENCODED_LEN {
27804 payload_buf[0..avail_len].copy_from_slice(__input);
27805 Bytes::new(&payload_buf)
27806 } else {
27807 Bytes::new(__input)
27808 };
27809 let mut __struct = Self::default();
27810 __struct.time_usec = buf.get_u64_le();
27811 for v in &mut __struct.distances {
27812 let val = buf.get_u16_le();
27813 *v = val;
27814 }
27815 __struct.min_distance = buf.get_u16_le();
27816 __struct.max_distance = buf.get_u16_le();
27817 let tmp = buf.get_u8();
27818 __struct.sensor_type =
27819 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
27820 enum_type: "MavDistanceSensor",
27821 value: tmp as u32,
27822 })?;
27823 __struct.increment = buf.get_u8();
27824 __struct.increment_f = buf.get_f32_le();
27825 __struct.angle_offset = buf.get_f32_le();
27826 let tmp = buf.get_u8();
27827 __struct.frame =
27828 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
27829 enum_type: "MavFrame",
27830 value: tmp as u32,
27831 })?;
27832 Ok(__struct)
27833 }
27834 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27835 let mut __tmp = BytesMut::new(bytes);
27836 #[allow(clippy::absurd_extreme_comparisons)]
27837 #[allow(unused_comparisons)]
27838 if __tmp.remaining() < Self::ENCODED_LEN {
27839 panic!(
27840 "buffer is too small (need {} bytes, but got {})",
27841 Self::ENCODED_LEN,
27842 __tmp.remaining(),
27843 )
27844 }
27845 __tmp.put_u64_le(self.time_usec);
27846 for val in &self.distances {
27847 __tmp.put_u16_le(*val);
27848 }
27849 __tmp.put_u16_le(self.min_distance);
27850 __tmp.put_u16_le(self.max_distance);
27851 __tmp.put_u8(self.sensor_type as u8);
27852 __tmp.put_u8(self.increment);
27853 __tmp.put_f32_le(self.increment_f);
27854 __tmp.put_f32_le(self.angle_offset);
27855 __tmp.put_u8(self.frame as u8);
27856 if matches!(version, MavlinkVersion::V2) {
27857 let len = __tmp.len();
27858 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27859 } else {
27860 __tmp.len()
27861 }
27862 }
27863}
27864#[doc = "id: 106"]
27865#[doc = "Optical flow from an angular rate flow sensor (e.g. PX4FLOW or mouse sensor)."]
27866#[derive(Debug, Clone, PartialEq)]
27867#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27868#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27869pub struct OPTICAL_FLOW_RAD_DATA {
27870 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
27871 pub time_usec: u64,
27872 #[doc = "Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the."]
27873 pub integration_time_us: u32,
27874 #[doc = "Flow around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)"]
27875 pub integrated_x: f32,
27876 #[doc = "Flow around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)"]
27877 pub integrated_y: f32,
27878 #[doc = "RH rotation around X axis"]
27879 pub integrated_xgyro: f32,
27880 #[doc = "RH rotation around Y axis"]
27881 pub integrated_ygyro: f32,
27882 #[doc = "RH rotation around Z axis"]
27883 pub integrated_zgyro: f32,
27884 #[doc = "Time since the distance was sampled."]
27885 pub time_delta_distance_us: u32,
27886 #[doc = "Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance."]
27887 pub distance: f32,
27888 #[doc = "Temperature"]
27889 pub temperature: i16,
27890 #[doc = "Sensor ID"]
27891 pub sensor_id: u8,
27892 #[doc = "Optical flow quality / confidence. 0: no valid flow, 255: maximum quality"]
27893 pub quality: u8,
27894}
27895impl OPTICAL_FLOW_RAD_DATA {
27896 pub const ENCODED_LEN: usize = 44usize;
27897 pub const DEFAULT: Self = Self {
27898 time_usec: 0_u64,
27899 integration_time_us: 0_u32,
27900 integrated_x: 0.0_f32,
27901 integrated_y: 0.0_f32,
27902 integrated_xgyro: 0.0_f32,
27903 integrated_ygyro: 0.0_f32,
27904 integrated_zgyro: 0.0_f32,
27905 time_delta_distance_us: 0_u32,
27906 distance: 0.0_f32,
27907 temperature: 0_i16,
27908 sensor_id: 0_u8,
27909 quality: 0_u8,
27910 };
27911 #[cfg(feature = "arbitrary")]
27912 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27913 use arbitrary::{Arbitrary, Unstructured};
27914 let mut buf = [0u8; 1024];
27915 rng.fill_bytes(&mut buf);
27916 let mut unstructured = Unstructured::new(&buf);
27917 Self::arbitrary(&mut unstructured).unwrap_or_default()
27918 }
27919}
27920impl Default for OPTICAL_FLOW_RAD_DATA {
27921 fn default() -> Self {
27922 Self::DEFAULT.clone()
27923 }
27924}
27925impl MessageData for OPTICAL_FLOW_RAD_DATA {
27926 type Message = MavMessage;
27927 const ID: u32 = 106u32;
27928 const NAME: &'static str = "OPTICAL_FLOW_RAD";
27929 const EXTRA_CRC: u8 = 138u8;
27930 const ENCODED_LEN: usize = 44usize;
27931 fn deser(
27932 _version: MavlinkVersion,
27933 __input: &[u8],
27934 ) -> Result<Self, ::mavlink_core::error::ParserError> {
27935 let avail_len = __input.len();
27936 let mut payload_buf = [0; Self::ENCODED_LEN];
27937 let mut buf = if avail_len < Self::ENCODED_LEN {
27938 payload_buf[0..avail_len].copy_from_slice(__input);
27939 Bytes::new(&payload_buf)
27940 } else {
27941 Bytes::new(__input)
27942 };
27943 let mut __struct = Self::default();
27944 __struct.time_usec = buf.get_u64_le();
27945 __struct.integration_time_us = buf.get_u32_le();
27946 __struct.integrated_x = buf.get_f32_le();
27947 __struct.integrated_y = buf.get_f32_le();
27948 __struct.integrated_xgyro = buf.get_f32_le();
27949 __struct.integrated_ygyro = buf.get_f32_le();
27950 __struct.integrated_zgyro = buf.get_f32_le();
27951 __struct.time_delta_distance_us = buf.get_u32_le();
27952 __struct.distance = buf.get_f32_le();
27953 __struct.temperature = buf.get_i16_le();
27954 __struct.sensor_id = buf.get_u8();
27955 __struct.quality = buf.get_u8();
27956 Ok(__struct)
27957 }
27958 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27959 let mut __tmp = BytesMut::new(bytes);
27960 #[allow(clippy::absurd_extreme_comparisons)]
27961 #[allow(unused_comparisons)]
27962 if __tmp.remaining() < Self::ENCODED_LEN {
27963 panic!(
27964 "buffer is too small (need {} bytes, but got {})",
27965 Self::ENCODED_LEN,
27966 __tmp.remaining(),
27967 )
27968 }
27969 __tmp.put_u64_le(self.time_usec);
27970 __tmp.put_u32_le(self.integration_time_us);
27971 __tmp.put_f32_le(self.integrated_x);
27972 __tmp.put_f32_le(self.integrated_y);
27973 __tmp.put_f32_le(self.integrated_xgyro);
27974 __tmp.put_f32_le(self.integrated_ygyro);
27975 __tmp.put_f32_le(self.integrated_zgyro);
27976 __tmp.put_u32_le(self.time_delta_distance_us);
27977 __tmp.put_f32_le(self.distance);
27978 __tmp.put_i16_le(self.temperature);
27979 __tmp.put_u8(self.sensor_id);
27980 __tmp.put_u8(self.quality);
27981 if matches!(version, MavlinkVersion::V2) {
27982 let len = __tmp.len();
27983 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27984 } else {
27985 __tmp.len()
27986 }
27987 }
27988}
27989#[doc = "id: 113"]
27990#[doc = "The global position, as returned by the Global Positioning System (GPS). This is NOT the global position estimate of the system, but rather a RAW sensor value. See message GLOBAL_POSITION_INT for the global position estimate."]
27991#[derive(Debug, Clone, PartialEq)]
27992#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27993#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27994pub struct HIL_GPS_DATA {
27995 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
27996 pub time_usec: u64,
27997 #[doc = "Latitude (WGS84)"]
27998 pub lat: i32,
27999 #[doc = "Longitude (WGS84)"]
28000 pub lon: i32,
28001 #[doc = "Altitude (MSL). Positive for up."]
28002 pub alt: i32,
28003 #[doc = "GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX"]
28004 pub eph: u16,
28005 #[doc = "GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX"]
28006 pub epv: u16,
28007 #[doc = "GPS ground speed. If unknown, set to: UINT16_MAX"]
28008 pub vel: u16,
28009 #[doc = "GPS velocity in north direction in earth-fixed NED frame"]
28010 pub vn: i16,
28011 #[doc = "GPS velocity in east direction in earth-fixed NED frame"]
28012 pub ve: i16,
28013 #[doc = "GPS velocity in down direction in earth-fixed NED frame"]
28014 pub vd: i16,
28015 #[doc = "Course over ground (NOT heading, but direction of movement), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX"]
28016 pub cog: u16,
28017 #[doc = "0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix."]
28018 pub fix_type: u8,
28019 #[doc = "Number of satellites visible. If unknown, set to UINT8_MAX"]
28020 pub satellites_visible: u8,
28021 #[doc = "GPS ID (zero indexed). Used for multiple GPS inputs"]
28022 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
28023 pub id: u8,
28024 #[doc = "Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north"]
28025 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
28026 pub yaw: u16,
28027}
28028impl HIL_GPS_DATA {
28029 pub const ENCODED_LEN: usize = 39usize;
28030 pub const DEFAULT: Self = Self {
28031 time_usec: 0_u64,
28032 lat: 0_i32,
28033 lon: 0_i32,
28034 alt: 0_i32,
28035 eph: 0_u16,
28036 epv: 0_u16,
28037 vel: 0_u16,
28038 vn: 0_i16,
28039 ve: 0_i16,
28040 vd: 0_i16,
28041 cog: 0_u16,
28042 fix_type: 0_u8,
28043 satellites_visible: 0_u8,
28044 id: 0_u8,
28045 yaw: 0_u16,
28046 };
28047 #[cfg(feature = "arbitrary")]
28048 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28049 use arbitrary::{Arbitrary, Unstructured};
28050 let mut buf = [0u8; 1024];
28051 rng.fill_bytes(&mut buf);
28052 let mut unstructured = Unstructured::new(&buf);
28053 Self::arbitrary(&mut unstructured).unwrap_or_default()
28054 }
28055}
28056impl Default for HIL_GPS_DATA {
28057 fn default() -> Self {
28058 Self::DEFAULT.clone()
28059 }
28060}
28061impl MessageData for HIL_GPS_DATA {
28062 type Message = MavMessage;
28063 const ID: u32 = 113u32;
28064 const NAME: &'static str = "HIL_GPS";
28065 const EXTRA_CRC: u8 = 124u8;
28066 const ENCODED_LEN: usize = 39usize;
28067 fn deser(
28068 _version: MavlinkVersion,
28069 __input: &[u8],
28070 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28071 let avail_len = __input.len();
28072 let mut payload_buf = [0; Self::ENCODED_LEN];
28073 let mut buf = if avail_len < Self::ENCODED_LEN {
28074 payload_buf[0..avail_len].copy_from_slice(__input);
28075 Bytes::new(&payload_buf)
28076 } else {
28077 Bytes::new(__input)
28078 };
28079 let mut __struct = Self::default();
28080 __struct.time_usec = buf.get_u64_le();
28081 __struct.lat = buf.get_i32_le();
28082 __struct.lon = buf.get_i32_le();
28083 __struct.alt = buf.get_i32_le();
28084 __struct.eph = buf.get_u16_le();
28085 __struct.epv = buf.get_u16_le();
28086 __struct.vel = buf.get_u16_le();
28087 __struct.vn = buf.get_i16_le();
28088 __struct.ve = buf.get_i16_le();
28089 __struct.vd = buf.get_i16_le();
28090 __struct.cog = buf.get_u16_le();
28091 __struct.fix_type = buf.get_u8();
28092 __struct.satellites_visible = buf.get_u8();
28093 __struct.id = buf.get_u8();
28094 __struct.yaw = buf.get_u16_le();
28095 Ok(__struct)
28096 }
28097 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28098 let mut __tmp = BytesMut::new(bytes);
28099 #[allow(clippy::absurd_extreme_comparisons)]
28100 #[allow(unused_comparisons)]
28101 if __tmp.remaining() < Self::ENCODED_LEN {
28102 panic!(
28103 "buffer is too small (need {} bytes, but got {})",
28104 Self::ENCODED_LEN,
28105 __tmp.remaining(),
28106 )
28107 }
28108 __tmp.put_u64_le(self.time_usec);
28109 __tmp.put_i32_le(self.lat);
28110 __tmp.put_i32_le(self.lon);
28111 __tmp.put_i32_le(self.alt);
28112 __tmp.put_u16_le(self.eph);
28113 __tmp.put_u16_le(self.epv);
28114 __tmp.put_u16_le(self.vel);
28115 __tmp.put_i16_le(self.vn);
28116 __tmp.put_i16_le(self.ve);
28117 __tmp.put_i16_le(self.vd);
28118 __tmp.put_u16_le(self.cog);
28119 __tmp.put_u8(self.fix_type);
28120 __tmp.put_u8(self.satellites_visible);
28121 __tmp.put_u8(self.id);
28122 __tmp.put_u16_le(self.yaw);
28123 if matches!(version, MavlinkVersion::V2) {
28124 let len = __tmp.len();
28125 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28126 } else {
28127 __tmp.len()
28128 }
28129 }
28130}
28131#[doc = "id: 9005"]
28132#[doc = "Winch status."]
28133#[derive(Debug, Clone, PartialEq)]
28134#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28135#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28136pub struct WINCH_STATUS_DATA {
28137 #[doc = "Timestamp (synced to UNIX time or since system boot)."]
28138 pub time_usec: u64,
28139 #[doc = "Length of line released. NaN if unknown"]
28140 pub line_length: f32,
28141 #[doc = "Speed line is being released or retracted. Positive values if being released, negative values if being retracted, NaN if unknown"]
28142 pub speed: f32,
28143 #[doc = "Tension on the line. NaN if unknown"]
28144 pub tension: f32,
28145 #[doc = "Voltage of the battery supplying the winch. NaN if unknown"]
28146 pub voltage: f32,
28147 #[doc = "Current draw from the winch. NaN if unknown"]
28148 pub current: f32,
28149 #[doc = "Status flags"]
28150 pub status: MavWinchStatusFlag,
28151 #[doc = "Temperature of the motor. INT16_MAX if unknown"]
28152 pub temperature: i16,
28153}
28154impl WINCH_STATUS_DATA {
28155 pub const ENCODED_LEN: usize = 34usize;
28156 pub const DEFAULT: Self = Self {
28157 time_usec: 0_u64,
28158 line_length: 0.0_f32,
28159 speed: 0.0_f32,
28160 tension: 0.0_f32,
28161 voltage: 0.0_f32,
28162 current: 0.0_f32,
28163 status: MavWinchStatusFlag::DEFAULT,
28164 temperature: 0_i16,
28165 };
28166 #[cfg(feature = "arbitrary")]
28167 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28168 use arbitrary::{Arbitrary, Unstructured};
28169 let mut buf = [0u8; 1024];
28170 rng.fill_bytes(&mut buf);
28171 let mut unstructured = Unstructured::new(&buf);
28172 Self::arbitrary(&mut unstructured).unwrap_or_default()
28173 }
28174}
28175impl Default for WINCH_STATUS_DATA {
28176 fn default() -> Self {
28177 Self::DEFAULT.clone()
28178 }
28179}
28180impl MessageData for WINCH_STATUS_DATA {
28181 type Message = MavMessage;
28182 const ID: u32 = 9005u32;
28183 const NAME: &'static str = "WINCH_STATUS";
28184 const EXTRA_CRC: u8 = 117u8;
28185 const ENCODED_LEN: usize = 34usize;
28186 fn deser(
28187 _version: MavlinkVersion,
28188 __input: &[u8],
28189 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28190 let avail_len = __input.len();
28191 let mut payload_buf = [0; Self::ENCODED_LEN];
28192 let mut buf = if avail_len < Self::ENCODED_LEN {
28193 payload_buf[0..avail_len].copy_from_slice(__input);
28194 Bytes::new(&payload_buf)
28195 } else {
28196 Bytes::new(__input)
28197 };
28198 let mut __struct = Self::default();
28199 __struct.time_usec = buf.get_u64_le();
28200 __struct.line_length = buf.get_f32_le();
28201 __struct.speed = buf.get_f32_le();
28202 __struct.tension = buf.get_f32_le();
28203 __struct.voltage = buf.get_f32_le();
28204 __struct.current = buf.get_f32_le();
28205 let tmp = buf.get_u32_le();
28206 __struct.status = MavWinchStatusFlag::from_bits(tmp & MavWinchStatusFlag::all().bits())
28207 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
28208 flag_type: "MavWinchStatusFlag",
28209 value: tmp as u32,
28210 })?;
28211 __struct.temperature = buf.get_i16_le();
28212 Ok(__struct)
28213 }
28214 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28215 let mut __tmp = BytesMut::new(bytes);
28216 #[allow(clippy::absurd_extreme_comparisons)]
28217 #[allow(unused_comparisons)]
28218 if __tmp.remaining() < Self::ENCODED_LEN {
28219 panic!(
28220 "buffer is too small (need {} bytes, but got {})",
28221 Self::ENCODED_LEN,
28222 __tmp.remaining(),
28223 )
28224 }
28225 __tmp.put_u64_le(self.time_usec);
28226 __tmp.put_f32_le(self.line_length);
28227 __tmp.put_f32_le(self.speed);
28228 __tmp.put_f32_le(self.tension);
28229 __tmp.put_f32_le(self.voltage);
28230 __tmp.put_f32_le(self.current);
28231 __tmp.put_u32_le(self.status.bits());
28232 __tmp.put_i16_le(self.temperature);
28233 if matches!(version, MavlinkVersion::V2) {
28234 let len = __tmp.len();
28235 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28236 } else {
28237 __tmp.len()
28238 }
28239 }
28240}
28241#[doc = "id: 373"]
28242#[doc = "Telemetry of power generation system. Alternator or mechanical generator."]
28243#[derive(Debug, Clone, PartialEq)]
28244#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28245#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28246pub struct GENERATOR_STATUS_DATA {
28247 #[doc = "Status flags."]
28248 pub status: MavGeneratorStatusFlag,
28249 #[doc = "Current into/out of battery. Positive for out. Negative for in. NaN: field not provided."]
28250 pub battery_current: f32,
28251 #[doc = "Current going to the UAV. If battery current not available this is the DC current from the generator. Positive for out. Negative for in. NaN: field not provided"]
28252 pub load_current: f32,
28253 #[doc = "The power being generated. NaN: field not provided"]
28254 pub power_generated: f32,
28255 #[doc = "Voltage of the bus seen at the generator, or battery bus if battery bus is controlled by generator and at a different voltage to main bus."]
28256 pub bus_voltage: f32,
28257 #[doc = "The target battery current. Positive for out. Negative for in. NaN: field not provided"]
28258 pub bat_current_setpoint: f32,
28259 #[doc = "Seconds this generator has run since it was rebooted. UINT32_MAX: field not provided."]
28260 pub runtime: u32,
28261 #[doc = "Seconds until this generator requires maintenance. A negative value indicates maintenance is past-due. INT32_MAX: field not provided."]
28262 pub time_until_maintenance: i32,
28263 #[doc = "Speed of electrical generator or alternator. UINT16_MAX: field not provided."]
28264 pub generator_speed: u16,
28265 #[doc = "The temperature of the rectifier or power converter. INT16_MAX: field not provided."]
28266 pub rectifier_temperature: i16,
28267 #[doc = "The temperature of the mechanical motor, fuel cell core or generator. INT16_MAX: field not provided."]
28268 pub generator_temperature: i16,
28269}
28270impl GENERATOR_STATUS_DATA {
28271 pub const ENCODED_LEN: usize = 42usize;
28272 pub const DEFAULT: Self = Self {
28273 status: MavGeneratorStatusFlag::DEFAULT,
28274 battery_current: 0.0_f32,
28275 load_current: 0.0_f32,
28276 power_generated: 0.0_f32,
28277 bus_voltage: 0.0_f32,
28278 bat_current_setpoint: 0.0_f32,
28279 runtime: 0_u32,
28280 time_until_maintenance: 0_i32,
28281 generator_speed: 0_u16,
28282 rectifier_temperature: 0_i16,
28283 generator_temperature: 0_i16,
28284 };
28285 #[cfg(feature = "arbitrary")]
28286 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28287 use arbitrary::{Arbitrary, Unstructured};
28288 let mut buf = [0u8; 1024];
28289 rng.fill_bytes(&mut buf);
28290 let mut unstructured = Unstructured::new(&buf);
28291 Self::arbitrary(&mut unstructured).unwrap_or_default()
28292 }
28293}
28294impl Default for GENERATOR_STATUS_DATA {
28295 fn default() -> Self {
28296 Self::DEFAULT.clone()
28297 }
28298}
28299impl MessageData for GENERATOR_STATUS_DATA {
28300 type Message = MavMessage;
28301 const ID: u32 = 373u32;
28302 const NAME: &'static str = "GENERATOR_STATUS";
28303 const EXTRA_CRC: u8 = 117u8;
28304 const ENCODED_LEN: usize = 42usize;
28305 fn deser(
28306 _version: MavlinkVersion,
28307 __input: &[u8],
28308 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28309 let avail_len = __input.len();
28310 let mut payload_buf = [0; Self::ENCODED_LEN];
28311 let mut buf = if avail_len < Self::ENCODED_LEN {
28312 payload_buf[0..avail_len].copy_from_slice(__input);
28313 Bytes::new(&payload_buf)
28314 } else {
28315 Bytes::new(__input)
28316 };
28317 let mut __struct = Self::default();
28318 let tmp = buf.get_u64_le();
28319 __struct.status = MavGeneratorStatusFlag::from_bits(
28320 tmp & MavGeneratorStatusFlag::all().bits(),
28321 )
28322 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
28323 flag_type: "MavGeneratorStatusFlag",
28324 value: tmp as u32,
28325 })?;
28326 __struct.battery_current = buf.get_f32_le();
28327 __struct.load_current = buf.get_f32_le();
28328 __struct.power_generated = buf.get_f32_le();
28329 __struct.bus_voltage = buf.get_f32_le();
28330 __struct.bat_current_setpoint = buf.get_f32_le();
28331 __struct.runtime = buf.get_u32_le();
28332 __struct.time_until_maintenance = buf.get_i32_le();
28333 __struct.generator_speed = buf.get_u16_le();
28334 __struct.rectifier_temperature = buf.get_i16_le();
28335 __struct.generator_temperature = buf.get_i16_le();
28336 Ok(__struct)
28337 }
28338 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28339 let mut __tmp = BytesMut::new(bytes);
28340 #[allow(clippy::absurd_extreme_comparisons)]
28341 #[allow(unused_comparisons)]
28342 if __tmp.remaining() < Self::ENCODED_LEN {
28343 panic!(
28344 "buffer is too small (need {} bytes, but got {})",
28345 Self::ENCODED_LEN,
28346 __tmp.remaining(),
28347 )
28348 }
28349 __tmp.put_u64_le(self.status.bits());
28350 __tmp.put_f32_le(self.battery_current);
28351 __tmp.put_f32_le(self.load_current);
28352 __tmp.put_f32_le(self.power_generated);
28353 __tmp.put_f32_le(self.bus_voltage);
28354 __tmp.put_f32_le(self.bat_current_setpoint);
28355 __tmp.put_u32_le(self.runtime);
28356 __tmp.put_i32_le(self.time_until_maintenance);
28357 __tmp.put_u16_le(self.generator_speed);
28358 __tmp.put_i16_le(self.rectifier_temperature);
28359 __tmp.put_i16_le(self.generator_temperature);
28360 if matches!(version, MavlinkVersion::V2) {
28361 let len = __tmp.len();
28362 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28363 } else {
28364 __tmp.len()
28365 }
28366 }
28367}
28368#[doc = "id: 110"]
28369#[doc = "File transfer protocol message: <https://mavlink.io/en/services/ftp.html>."]
28370#[derive(Debug, Clone, PartialEq)]
28371#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28372#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28373pub struct FILE_TRANSFER_PROTOCOL_DATA {
28374 #[doc = "Network ID (0 for broadcast)"]
28375 pub target_network: u8,
28376 #[doc = "System ID (0 for broadcast)"]
28377 pub target_system: u8,
28378 #[doc = "Component ID (0 for broadcast)"]
28379 pub target_component: u8,
28380 #[doc = "Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The content/format of this block is defined in <https://mavlink.io/en/services/ftp.html>."]
28381 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
28382 pub payload: [u8; 251],
28383}
28384impl FILE_TRANSFER_PROTOCOL_DATA {
28385 pub const ENCODED_LEN: usize = 254usize;
28386 pub const DEFAULT: Self = Self {
28387 target_network: 0_u8,
28388 target_system: 0_u8,
28389 target_component: 0_u8,
28390 payload: [0_u8; 251usize],
28391 };
28392 #[cfg(feature = "arbitrary")]
28393 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28394 use arbitrary::{Arbitrary, Unstructured};
28395 let mut buf = [0u8; 1024];
28396 rng.fill_bytes(&mut buf);
28397 let mut unstructured = Unstructured::new(&buf);
28398 Self::arbitrary(&mut unstructured).unwrap_or_default()
28399 }
28400}
28401impl Default for FILE_TRANSFER_PROTOCOL_DATA {
28402 fn default() -> Self {
28403 Self::DEFAULT.clone()
28404 }
28405}
28406impl MessageData for FILE_TRANSFER_PROTOCOL_DATA {
28407 type Message = MavMessage;
28408 const ID: u32 = 110u32;
28409 const NAME: &'static str = "FILE_TRANSFER_PROTOCOL";
28410 const EXTRA_CRC: u8 = 84u8;
28411 const ENCODED_LEN: usize = 254usize;
28412 fn deser(
28413 _version: MavlinkVersion,
28414 __input: &[u8],
28415 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28416 let avail_len = __input.len();
28417 let mut payload_buf = [0; Self::ENCODED_LEN];
28418 let mut buf = if avail_len < Self::ENCODED_LEN {
28419 payload_buf[0..avail_len].copy_from_slice(__input);
28420 Bytes::new(&payload_buf)
28421 } else {
28422 Bytes::new(__input)
28423 };
28424 let mut __struct = Self::default();
28425 __struct.target_network = buf.get_u8();
28426 __struct.target_system = buf.get_u8();
28427 __struct.target_component = buf.get_u8();
28428 for v in &mut __struct.payload {
28429 let val = buf.get_u8();
28430 *v = val;
28431 }
28432 Ok(__struct)
28433 }
28434 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28435 let mut __tmp = BytesMut::new(bytes);
28436 #[allow(clippy::absurd_extreme_comparisons)]
28437 #[allow(unused_comparisons)]
28438 if __tmp.remaining() < Self::ENCODED_LEN {
28439 panic!(
28440 "buffer is too small (need {} bytes, but got {})",
28441 Self::ENCODED_LEN,
28442 __tmp.remaining(),
28443 )
28444 }
28445 __tmp.put_u8(self.target_network);
28446 __tmp.put_u8(self.target_system);
28447 __tmp.put_u8(self.target_component);
28448 for val in &self.payload {
28449 __tmp.put_u8(*val);
28450 }
28451 if matches!(version, MavlinkVersion::V2) {
28452 let len = __tmp.len();
28453 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28454 } else {
28455 __tmp.len()
28456 }
28457 }
28458}
28459#[doc = "id: 130"]
28460#[doc = "Handshake message to initiate, control and stop image streaming when using the Image Transmission Protocol: <https://mavlink.io/en/services/image_transmission.html>."]
28461#[derive(Debug, Clone, PartialEq)]
28462#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28463#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28464pub struct DATA_TRANSMISSION_HANDSHAKE_DATA {
28465 #[doc = "total data size (set on ACK only)."]
28466 pub size: u32,
28467 #[doc = "Width of a matrix or image."]
28468 pub width: u16,
28469 #[doc = "Height of a matrix or image."]
28470 pub height: u16,
28471 #[doc = "Number of packets being sent (set on ACK only)."]
28472 pub packets: u16,
28473 #[doc = "Type of requested/acknowledged data."]
28474 pub mavtype: MavlinkDataStreamType,
28475 #[doc = "Payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)."]
28476 pub payload: u8,
28477 #[doc = "JPEG quality. Values: [1-100]."]
28478 pub jpg_quality: u8,
28479}
28480impl DATA_TRANSMISSION_HANDSHAKE_DATA {
28481 pub const ENCODED_LEN: usize = 13usize;
28482 pub const DEFAULT: Self = Self {
28483 size: 0_u32,
28484 width: 0_u16,
28485 height: 0_u16,
28486 packets: 0_u16,
28487 mavtype: MavlinkDataStreamType::DEFAULT,
28488 payload: 0_u8,
28489 jpg_quality: 0_u8,
28490 };
28491 #[cfg(feature = "arbitrary")]
28492 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28493 use arbitrary::{Arbitrary, Unstructured};
28494 let mut buf = [0u8; 1024];
28495 rng.fill_bytes(&mut buf);
28496 let mut unstructured = Unstructured::new(&buf);
28497 Self::arbitrary(&mut unstructured).unwrap_or_default()
28498 }
28499}
28500impl Default for DATA_TRANSMISSION_HANDSHAKE_DATA {
28501 fn default() -> Self {
28502 Self::DEFAULT.clone()
28503 }
28504}
28505impl MessageData for DATA_TRANSMISSION_HANDSHAKE_DATA {
28506 type Message = MavMessage;
28507 const ID: u32 = 130u32;
28508 const NAME: &'static str = "DATA_TRANSMISSION_HANDSHAKE";
28509 const EXTRA_CRC: u8 = 29u8;
28510 const ENCODED_LEN: usize = 13usize;
28511 fn deser(
28512 _version: MavlinkVersion,
28513 __input: &[u8],
28514 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28515 let avail_len = __input.len();
28516 let mut payload_buf = [0; Self::ENCODED_LEN];
28517 let mut buf = if avail_len < Self::ENCODED_LEN {
28518 payload_buf[0..avail_len].copy_from_slice(__input);
28519 Bytes::new(&payload_buf)
28520 } else {
28521 Bytes::new(__input)
28522 };
28523 let mut __struct = Self::default();
28524 __struct.size = buf.get_u32_le();
28525 __struct.width = buf.get_u16_le();
28526 __struct.height = buf.get_u16_le();
28527 __struct.packets = buf.get_u16_le();
28528 let tmp = buf.get_u8();
28529 __struct.mavtype =
28530 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
28531 enum_type: "MavlinkDataStreamType",
28532 value: tmp as u32,
28533 })?;
28534 __struct.payload = buf.get_u8();
28535 __struct.jpg_quality = buf.get_u8();
28536 Ok(__struct)
28537 }
28538 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28539 let mut __tmp = BytesMut::new(bytes);
28540 #[allow(clippy::absurd_extreme_comparisons)]
28541 #[allow(unused_comparisons)]
28542 if __tmp.remaining() < Self::ENCODED_LEN {
28543 panic!(
28544 "buffer is too small (need {} bytes, but got {})",
28545 Self::ENCODED_LEN,
28546 __tmp.remaining(),
28547 )
28548 }
28549 __tmp.put_u32_le(self.size);
28550 __tmp.put_u16_le(self.width);
28551 __tmp.put_u16_le(self.height);
28552 __tmp.put_u16_le(self.packets);
28553 __tmp.put_u8(self.mavtype as u8);
28554 __tmp.put_u8(self.payload);
28555 __tmp.put_u8(self.jpg_quality);
28556 if matches!(version, MavlinkVersion::V2) {
28557 let len = __tmp.len();
28558 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28559 } else {
28560 __tmp.len()
28561 }
28562 }
28563}
28564#[doc = "id: 401"]
28565#[doc = "Tune formats supported by vehicle. This should be emitted as response to MAV_CMD_REQUEST_MESSAGE."]
28566#[derive(Debug, Clone, PartialEq)]
28567#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28568#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28569pub struct SUPPORTED_TUNES_DATA {
28570 #[doc = "Bitfield of supported tune formats."]
28571 pub format: TuneFormat,
28572 #[doc = "System ID"]
28573 pub target_system: u8,
28574 #[doc = "Component ID"]
28575 pub target_component: u8,
28576}
28577impl SUPPORTED_TUNES_DATA {
28578 pub const ENCODED_LEN: usize = 6usize;
28579 pub const DEFAULT: Self = Self {
28580 format: TuneFormat::DEFAULT,
28581 target_system: 0_u8,
28582 target_component: 0_u8,
28583 };
28584 #[cfg(feature = "arbitrary")]
28585 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28586 use arbitrary::{Arbitrary, Unstructured};
28587 let mut buf = [0u8; 1024];
28588 rng.fill_bytes(&mut buf);
28589 let mut unstructured = Unstructured::new(&buf);
28590 Self::arbitrary(&mut unstructured).unwrap_or_default()
28591 }
28592}
28593impl Default for SUPPORTED_TUNES_DATA {
28594 fn default() -> Self {
28595 Self::DEFAULT.clone()
28596 }
28597}
28598impl MessageData for SUPPORTED_TUNES_DATA {
28599 type Message = MavMessage;
28600 const ID: u32 = 401u32;
28601 const NAME: &'static str = "SUPPORTED_TUNES";
28602 const EXTRA_CRC: u8 = 183u8;
28603 const ENCODED_LEN: usize = 6usize;
28604 fn deser(
28605 _version: MavlinkVersion,
28606 __input: &[u8],
28607 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28608 let avail_len = __input.len();
28609 let mut payload_buf = [0; Self::ENCODED_LEN];
28610 let mut buf = if avail_len < Self::ENCODED_LEN {
28611 payload_buf[0..avail_len].copy_from_slice(__input);
28612 Bytes::new(&payload_buf)
28613 } else {
28614 Bytes::new(__input)
28615 };
28616 let mut __struct = Self::default();
28617 let tmp = buf.get_u32_le();
28618 __struct.format = FromPrimitive::from_u32(tmp).ok_or(
28619 ::mavlink_core::error::ParserError::InvalidEnum {
28620 enum_type: "TuneFormat",
28621 value: tmp as u32,
28622 },
28623 )?;
28624 __struct.target_system = buf.get_u8();
28625 __struct.target_component = buf.get_u8();
28626 Ok(__struct)
28627 }
28628 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28629 let mut __tmp = BytesMut::new(bytes);
28630 #[allow(clippy::absurd_extreme_comparisons)]
28631 #[allow(unused_comparisons)]
28632 if __tmp.remaining() < Self::ENCODED_LEN {
28633 panic!(
28634 "buffer is too small (need {} bytes, but got {})",
28635 Self::ENCODED_LEN,
28636 __tmp.remaining(),
28637 )
28638 }
28639 __tmp.put_u32_le(self.format as u32);
28640 __tmp.put_u8(self.target_system);
28641 __tmp.put_u8(self.target_component);
28642 if matches!(version, MavlinkVersion::V2) {
28643 let len = __tmp.len();
28644 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28645 } else {
28646 __tmp.len()
28647 }
28648 }
28649}
28650#[doc = "id: 48"]
28651#[doc = "Sets the GPS coordinates of the vehicle local origin (0,0,0) position. Vehicle should emit GPS_GLOBAL_ORIGIN irrespective of whether the origin is changed. This enables transform between the local coordinate frame and the global (GPS) coordinate frame, which may be necessary when (for example) indoor and outdoor settings are connected and the MAV should move from in- to outdoor."]
28652#[derive(Debug, Clone, PartialEq)]
28653#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28654#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28655pub struct SET_GPS_GLOBAL_ORIGIN_DATA {
28656 #[doc = "Latitude (WGS84)"]
28657 pub latitude: i32,
28658 #[doc = "Longitude (WGS84)"]
28659 pub longitude: i32,
28660 #[doc = "Altitude (MSL). Positive for up."]
28661 pub altitude: i32,
28662 #[doc = "System ID"]
28663 pub target_system: u8,
28664 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
28665 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
28666 pub time_usec: u64,
28667}
28668impl SET_GPS_GLOBAL_ORIGIN_DATA {
28669 pub const ENCODED_LEN: usize = 21usize;
28670 pub const DEFAULT: Self = Self {
28671 latitude: 0_i32,
28672 longitude: 0_i32,
28673 altitude: 0_i32,
28674 target_system: 0_u8,
28675 time_usec: 0_u64,
28676 };
28677 #[cfg(feature = "arbitrary")]
28678 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28679 use arbitrary::{Arbitrary, Unstructured};
28680 let mut buf = [0u8; 1024];
28681 rng.fill_bytes(&mut buf);
28682 let mut unstructured = Unstructured::new(&buf);
28683 Self::arbitrary(&mut unstructured).unwrap_or_default()
28684 }
28685}
28686impl Default for SET_GPS_GLOBAL_ORIGIN_DATA {
28687 fn default() -> Self {
28688 Self::DEFAULT.clone()
28689 }
28690}
28691impl MessageData for SET_GPS_GLOBAL_ORIGIN_DATA {
28692 type Message = MavMessage;
28693 const ID: u32 = 48u32;
28694 const NAME: &'static str = "SET_GPS_GLOBAL_ORIGIN";
28695 const EXTRA_CRC: u8 = 41u8;
28696 const ENCODED_LEN: usize = 21usize;
28697 fn deser(
28698 _version: MavlinkVersion,
28699 __input: &[u8],
28700 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28701 let avail_len = __input.len();
28702 let mut payload_buf = [0; Self::ENCODED_LEN];
28703 let mut buf = if avail_len < Self::ENCODED_LEN {
28704 payload_buf[0..avail_len].copy_from_slice(__input);
28705 Bytes::new(&payload_buf)
28706 } else {
28707 Bytes::new(__input)
28708 };
28709 let mut __struct = Self::default();
28710 __struct.latitude = buf.get_i32_le();
28711 __struct.longitude = buf.get_i32_le();
28712 __struct.altitude = buf.get_i32_le();
28713 __struct.target_system = buf.get_u8();
28714 __struct.time_usec = buf.get_u64_le();
28715 Ok(__struct)
28716 }
28717 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28718 let mut __tmp = BytesMut::new(bytes);
28719 #[allow(clippy::absurd_extreme_comparisons)]
28720 #[allow(unused_comparisons)]
28721 if __tmp.remaining() < Self::ENCODED_LEN {
28722 panic!(
28723 "buffer is too small (need {} bytes, but got {})",
28724 Self::ENCODED_LEN,
28725 __tmp.remaining(),
28726 )
28727 }
28728 __tmp.put_i32_le(self.latitude);
28729 __tmp.put_i32_le(self.longitude);
28730 __tmp.put_i32_le(self.altitude);
28731 __tmp.put_u8(self.target_system);
28732 __tmp.put_u64_le(self.time_usec);
28733 if matches!(version, MavlinkVersion::V2) {
28734 let len = __tmp.len();
28735 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28736 } else {
28737 __tmp.len()
28738 }
28739 }
28740}
28741#[doc = "id: 31"]
28742#[doc = "The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0)."]
28743#[derive(Debug, Clone, PartialEq)]
28744#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28745#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28746pub struct ATTITUDE_QUATERNION_DATA {
28747 #[doc = "Timestamp (time since system boot)."]
28748 pub time_boot_ms: u32,
28749 #[doc = "Quaternion component 1, w (1 in null-rotation)"]
28750 pub q1: f32,
28751 #[doc = "Quaternion component 2, x (0 in null-rotation)"]
28752 pub q2: f32,
28753 #[doc = "Quaternion component 3, y (0 in null-rotation)"]
28754 pub q3: f32,
28755 #[doc = "Quaternion component 4, z (0 in null-rotation)"]
28756 pub q4: f32,
28757 #[doc = "Roll angular speed"]
28758 pub rollspeed: f32,
28759 #[doc = "Pitch angular speed"]
28760 pub pitchspeed: f32,
28761 #[doc = "Yaw angular speed"]
28762 pub yawspeed: f32,
28763 #[doc = "Rotation offset by which the attitude quaternion and angular speed vector should be rotated for user display (quaternion with [w, x, y, z] order, zero-rotation is [1, 0, 0, 0], send [0, 0, 0, 0] if field not supported). This field is intended for systems in which the reference attitude may change during flight. For example, tailsitters VTOLs rotate their reference attitude by 90 degrees between hover mode and fixed wing mode, thus repr_offset_q is equal to [1, 0, 0, 0] in hover mode and equal to [0.7071, 0, 0.7071, 0] in fixed wing mode."]
28764 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
28765 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
28766 pub repr_offset_q: [f32; 4],
28767}
28768impl ATTITUDE_QUATERNION_DATA {
28769 pub const ENCODED_LEN: usize = 48usize;
28770 pub const DEFAULT: Self = Self {
28771 time_boot_ms: 0_u32,
28772 q1: 0.0_f32,
28773 q2: 0.0_f32,
28774 q3: 0.0_f32,
28775 q4: 0.0_f32,
28776 rollspeed: 0.0_f32,
28777 pitchspeed: 0.0_f32,
28778 yawspeed: 0.0_f32,
28779 repr_offset_q: [0.0_f32; 4usize],
28780 };
28781 #[cfg(feature = "arbitrary")]
28782 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28783 use arbitrary::{Arbitrary, Unstructured};
28784 let mut buf = [0u8; 1024];
28785 rng.fill_bytes(&mut buf);
28786 let mut unstructured = Unstructured::new(&buf);
28787 Self::arbitrary(&mut unstructured).unwrap_or_default()
28788 }
28789}
28790impl Default for ATTITUDE_QUATERNION_DATA {
28791 fn default() -> Self {
28792 Self::DEFAULT.clone()
28793 }
28794}
28795impl MessageData for ATTITUDE_QUATERNION_DATA {
28796 type Message = MavMessage;
28797 const ID: u32 = 31u32;
28798 const NAME: &'static str = "ATTITUDE_QUATERNION";
28799 const EXTRA_CRC: u8 = 246u8;
28800 const ENCODED_LEN: usize = 48usize;
28801 fn deser(
28802 _version: MavlinkVersion,
28803 __input: &[u8],
28804 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28805 let avail_len = __input.len();
28806 let mut payload_buf = [0; Self::ENCODED_LEN];
28807 let mut buf = if avail_len < Self::ENCODED_LEN {
28808 payload_buf[0..avail_len].copy_from_slice(__input);
28809 Bytes::new(&payload_buf)
28810 } else {
28811 Bytes::new(__input)
28812 };
28813 let mut __struct = Self::default();
28814 __struct.time_boot_ms = buf.get_u32_le();
28815 __struct.q1 = buf.get_f32_le();
28816 __struct.q2 = buf.get_f32_le();
28817 __struct.q3 = buf.get_f32_le();
28818 __struct.q4 = buf.get_f32_le();
28819 __struct.rollspeed = buf.get_f32_le();
28820 __struct.pitchspeed = buf.get_f32_le();
28821 __struct.yawspeed = buf.get_f32_le();
28822 for v in &mut __struct.repr_offset_q {
28823 let val = buf.get_f32_le();
28824 *v = val;
28825 }
28826 Ok(__struct)
28827 }
28828 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28829 let mut __tmp = BytesMut::new(bytes);
28830 #[allow(clippy::absurd_extreme_comparisons)]
28831 #[allow(unused_comparisons)]
28832 if __tmp.remaining() < Self::ENCODED_LEN {
28833 panic!(
28834 "buffer is too small (need {} bytes, but got {})",
28835 Self::ENCODED_LEN,
28836 __tmp.remaining(),
28837 )
28838 }
28839 __tmp.put_u32_le(self.time_boot_ms);
28840 __tmp.put_f32_le(self.q1);
28841 __tmp.put_f32_le(self.q2);
28842 __tmp.put_f32_le(self.q3);
28843 __tmp.put_f32_le(self.q4);
28844 __tmp.put_f32_le(self.rollspeed);
28845 __tmp.put_f32_le(self.pitchspeed);
28846 __tmp.put_f32_le(self.yawspeed);
28847 for val in &self.repr_offset_q {
28848 __tmp.put_f32_le(*val);
28849 }
28850 if matches!(version, MavlinkVersion::V2) {
28851 let len = __tmp.len();
28852 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28853 } else {
28854 __tmp.len()
28855 }
28856 }
28857}
28858#[doc = "id: 333"]
28859#[doc = "Describe a trajectory using an array of up-to 5 bezier control points in the local frame (MAV_FRAME_LOCAL_NED)."]
28860#[derive(Debug, Clone, PartialEq)]
28861#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28862#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28863pub struct TRAJECTORY_REPRESENTATION_BEZIER_DATA {
28864 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
28865 pub time_usec: u64,
28866 #[doc = "X-coordinate of bezier control points. Set to NaN if not being used"]
28867 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
28868 pub pos_x: [f32; 5],
28869 #[doc = "Y-coordinate of bezier control points. Set to NaN if not being used"]
28870 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
28871 pub pos_y: [f32; 5],
28872 #[doc = "Z-coordinate of bezier control points. Set to NaN if not being used"]
28873 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
28874 pub pos_z: [f32; 5],
28875 #[doc = "Bezier time horizon. Set to NaN if velocity/acceleration should not be incorporated"]
28876 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
28877 pub delta: [f32; 5],
28878 #[doc = "Yaw. Set to NaN for unchanged"]
28879 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
28880 pub pos_yaw: [f32; 5],
28881 #[doc = "Number of valid control points (up-to 5 points are possible)"]
28882 pub valid_points: u8,
28883}
28884impl TRAJECTORY_REPRESENTATION_BEZIER_DATA {
28885 pub const ENCODED_LEN: usize = 109usize;
28886 pub const DEFAULT: Self = Self {
28887 time_usec: 0_u64,
28888 pos_x: [0.0_f32; 5usize],
28889 pos_y: [0.0_f32; 5usize],
28890 pos_z: [0.0_f32; 5usize],
28891 delta: [0.0_f32; 5usize],
28892 pos_yaw: [0.0_f32; 5usize],
28893 valid_points: 0_u8,
28894 };
28895 #[cfg(feature = "arbitrary")]
28896 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28897 use arbitrary::{Arbitrary, Unstructured};
28898 let mut buf = [0u8; 1024];
28899 rng.fill_bytes(&mut buf);
28900 let mut unstructured = Unstructured::new(&buf);
28901 Self::arbitrary(&mut unstructured).unwrap_or_default()
28902 }
28903}
28904impl Default for TRAJECTORY_REPRESENTATION_BEZIER_DATA {
28905 fn default() -> Self {
28906 Self::DEFAULT.clone()
28907 }
28908}
28909impl MessageData for TRAJECTORY_REPRESENTATION_BEZIER_DATA {
28910 type Message = MavMessage;
28911 const ID: u32 = 333u32;
28912 const NAME: &'static str = "TRAJECTORY_REPRESENTATION_BEZIER";
28913 const EXTRA_CRC: u8 = 231u8;
28914 const ENCODED_LEN: usize = 109usize;
28915 fn deser(
28916 _version: MavlinkVersion,
28917 __input: &[u8],
28918 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28919 let avail_len = __input.len();
28920 let mut payload_buf = [0; Self::ENCODED_LEN];
28921 let mut buf = if avail_len < Self::ENCODED_LEN {
28922 payload_buf[0..avail_len].copy_from_slice(__input);
28923 Bytes::new(&payload_buf)
28924 } else {
28925 Bytes::new(__input)
28926 };
28927 let mut __struct = Self::default();
28928 __struct.time_usec = buf.get_u64_le();
28929 for v in &mut __struct.pos_x {
28930 let val = buf.get_f32_le();
28931 *v = val;
28932 }
28933 for v in &mut __struct.pos_y {
28934 let val = buf.get_f32_le();
28935 *v = val;
28936 }
28937 for v in &mut __struct.pos_z {
28938 let val = buf.get_f32_le();
28939 *v = val;
28940 }
28941 for v in &mut __struct.delta {
28942 let val = buf.get_f32_le();
28943 *v = val;
28944 }
28945 for v in &mut __struct.pos_yaw {
28946 let val = buf.get_f32_le();
28947 *v = val;
28948 }
28949 __struct.valid_points = buf.get_u8();
28950 Ok(__struct)
28951 }
28952 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28953 let mut __tmp = BytesMut::new(bytes);
28954 #[allow(clippy::absurd_extreme_comparisons)]
28955 #[allow(unused_comparisons)]
28956 if __tmp.remaining() < Self::ENCODED_LEN {
28957 panic!(
28958 "buffer is too small (need {} bytes, but got {})",
28959 Self::ENCODED_LEN,
28960 __tmp.remaining(),
28961 )
28962 }
28963 __tmp.put_u64_le(self.time_usec);
28964 for val in &self.pos_x {
28965 __tmp.put_f32_le(*val);
28966 }
28967 for val in &self.pos_y {
28968 __tmp.put_f32_le(*val);
28969 }
28970 for val in &self.pos_z {
28971 __tmp.put_f32_le(*val);
28972 }
28973 for val in &self.delta {
28974 __tmp.put_f32_le(*val);
28975 }
28976 for val in &self.pos_yaw {
28977 __tmp.put_f32_le(*val);
28978 }
28979 __tmp.put_u8(self.valid_points);
28980 if matches!(version, MavlinkVersion::V2) {
28981 let len = __tmp.len();
28982 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28983 } else {
28984 __tmp.len()
28985 }
28986 }
28987}
28988#[doc = "id: 371"]
28989#[doc = "Fuel status. This message provides \"generic\" fuel level information for in a GCS and for triggering failsafes in an autopilot. The fuel type and associated units for fields in this message are defined in the enum MAV_FUEL_TYPE. The reported `consumed_fuel` and `remaining_fuel` must only be supplied if measured: they must not be inferred from the `maximum_fuel` and the other value. A recipient can assume that if these fields are supplied they are accurate. If not provided, the recipient can infer `remaining_fuel` from `maximum_fuel` and `consumed_fuel` on the assumption that the fuel was initially at its maximum (this is what battery monitors assume). Note however that this is an assumption, and the UI should prompt the user appropriately (i.e. notify user that they should fill the tank before boot). This kind of information may also be sent in fuel-specific messages such as BATTERY_STATUS_V2. If both messages are sent for the same fuel system, the ids and corresponding information must match. This should be streamed (nominally at 0.1 Hz)."]
28990#[derive(Debug, Clone, PartialEq)]
28991#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28992#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28993pub struct FUEL_STATUS_DATA {
28994 #[doc = "Capacity when full. Must be provided."]
28995 pub maximum_fuel: f32,
28996 #[doc = "Consumed fuel (measured). This value should not be inferred: if not measured set to NaN. NaN: field not provided."]
28997 pub consumed_fuel: f32,
28998 #[doc = "Remaining fuel until empty (measured). The value should not be inferred: if not measured set to NaN. NaN: field not provided."]
28999 pub remaining_fuel: f32,
29000 #[doc = "Positive value when emptying/using, and negative if filling/replacing. NaN: field not provided."]
29001 pub flow_rate: f32,
29002 #[doc = "Fuel temperature. NaN: field not provided."]
29003 pub temperature: f32,
29004 #[doc = "Fuel type. Defines units for fuel capacity and consumption fields above."]
29005 pub fuel_type: MavFuelType,
29006 #[doc = "Fuel ID. Must match ID of other messages for same fuel system, such as BATTERY_STATUS_V2."]
29007 pub id: u8,
29008 #[doc = "Percentage of remaining fuel, relative to full. Values: [0-100], UINT8_MAX: field not provided."]
29009 pub percent_remaining: u8,
29010}
29011impl FUEL_STATUS_DATA {
29012 pub const ENCODED_LEN: usize = 26usize;
29013 pub const DEFAULT: Self = Self {
29014 maximum_fuel: 0.0_f32,
29015 consumed_fuel: 0.0_f32,
29016 remaining_fuel: 0.0_f32,
29017 flow_rate: 0.0_f32,
29018 temperature: 0.0_f32,
29019 fuel_type: MavFuelType::DEFAULT,
29020 id: 0_u8,
29021 percent_remaining: 0_u8,
29022 };
29023 #[cfg(feature = "arbitrary")]
29024 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29025 use arbitrary::{Arbitrary, Unstructured};
29026 let mut buf = [0u8; 1024];
29027 rng.fill_bytes(&mut buf);
29028 let mut unstructured = Unstructured::new(&buf);
29029 Self::arbitrary(&mut unstructured).unwrap_or_default()
29030 }
29031}
29032impl Default for FUEL_STATUS_DATA {
29033 fn default() -> Self {
29034 Self::DEFAULT.clone()
29035 }
29036}
29037impl MessageData for FUEL_STATUS_DATA {
29038 type Message = MavMessage;
29039 const ID: u32 = 371u32;
29040 const NAME: &'static str = "FUEL_STATUS";
29041 const EXTRA_CRC: u8 = 10u8;
29042 const ENCODED_LEN: usize = 26usize;
29043 fn deser(
29044 _version: MavlinkVersion,
29045 __input: &[u8],
29046 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29047 let avail_len = __input.len();
29048 let mut payload_buf = [0; Self::ENCODED_LEN];
29049 let mut buf = if avail_len < Self::ENCODED_LEN {
29050 payload_buf[0..avail_len].copy_from_slice(__input);
29051 Bytes::new(&payload_buf)
29052 } else {
29053 Bytes::new(__input)
29054 };
29055 let mut __struct = Self::default();
29056 __struct.maximum_fuel = buf.get_f32_le();
29057 __struct.consumed_fuel = buf.get_f32_le();
29058 __struct.remaining_fuel = buf.get_f32_le();
29059 __struct.flow_rate = buf.get_f32_le();
29060 __struct.temperature = buf.get_f32_le();
29061 let tmp = buf.get_u32_le();
29062 __struct.fuel_type = FromPrimitive::from_u32(tmp).ok_or(
29063 ::mavlink_core::error::ParserError::InvalidEnum {
29064 enum_type: "MavFuelType",
29065 value: tmp as u32,
29066 },
29067 )?;
29068 __struct.id = buf.get_u8();
29069 __struct.percent_remaining = buf.get_u8();
29070 Ok(__struct)
29071 }
29072 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29073 let mut __tmp = BytesMut::new(bytes);
29074 #[allow(clippy::absurd_extreme_comparisons)]
29075 #[allow(unused_comparisons)]
29076 if __tmp.remaining() < Self::ENCODED_LEN {
29077 panic!(
29078 "buffer is too small (need {} bytes, but got {})",
29079 Self::ENCODED_LEN,
29080 __tmp.remaining(),
29081 )
29082 }
29083 __tmp.put_f32_le(self.maximum_fuel);
29084 __tmp.put_f32_le(self.consumed_fuel);
29085 __tmp.put_f32_le(self.remaining_fuel);
29086 __tmp.put_f32_le(self.flow_rate);
29087 __tmp.put_f32_le(self.temperature);
29088 __tmp.put_u32_le(self.fuel_type as u32);
29089 __tmp.put_u8(self.id);
29090 __tmp.put_u8(self.percent_remaining);
29091 if matches!(version, MavlinkVersion::V2) {
29092 let len = __tmp.len();
29093 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29094 } else {
29095 __tmp.len()
29096 }
29097 }
29098}
29099#[doc = "id: 45"]
29100#[doc = "Delete all mission items at once."]
29101#[derive(Debug, Clone, PartialEq)]
29102#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29103#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29104pub struct MISSION_CLEAR_ALL_DATA {
29105 #[doc = "System ID"]
29106 pub target_system: u8,
29107 #[doc = "Component ID"]
29108 pub target_component: u8,
29109 #[doc = "Mission type."]
29110 #[cfg_attr(feature = "serde", serde(default))]
29111 pub mission_type: MavMissionType,
29112}
29113impl MISSION_CLEAR_ALL_DATA {
29114 pub const ENCODED_LEN: usize = 3usize;
29115 pub const DEFAULT: Self = Self {
29116 target_system: 0_u8,
29117 target_component: 0_u8,
29118 mission_type: MavMissionType::DEFAULT,
29119 };
29120 #[cfg(feature = "arbitrary")]
29121 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29122 use arbitrary::{Arbitrary, Unstructured};
29123 let mut buf = [0u8; 1024];
29124 rng.fill_bytes(&mut buf);
29125 let mut unstructured = Unstructured::new(&buf);
29126 Self::arbitrary(&mut unstructured).unwrap_or_default()
29127 }
29128}
29129impl Default for MISSION_CLEAR_ALL_DATA {
29130 fn default() -> Self {
29131 Self::DEFAULT.clone()
29132 }
29133}
29134impl MessageData for MISSION_CLEAR_ALL_DATA {
29135 type Message = MavMessage;
29136 const ID: u32 = 45u32;
29137 const NAME: &'static str = "MISSION_CLEAR_ALL";
29138 const EXTRA_CRC: u8 = 232u8;
29139 const ENCODED_LEN: usize = 3usize;
29140 fn deser(
29141 _version: MavlinkVersion,
29142 __input: &[u8],
29143 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29144 let avail_len = __input.len();
29145 let mut payload_buf = [0; Self::ENCODED_LEN];
29146 let mut buf = if avail_len < Self::ENCODED_LEN {
29147 payload_buf[0..avail_len].copy_from_slice(__input);
29148 Bytes::new(&payload_buf)
29149 } else {
29150 Bytes::new(__input)
29151 };
29152 let mut __struct = Self::default();
29153 __struct.target_system = buf.get_u8();
29154 __struct.target_component = buf.get_u8();
29155 let tmp = buf.get_u8();
29156 __struct.mission_type =
29157 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
29158 enum_type: "MavMissionType",
29159 value: tmp as u32,
29160 })?;
29161 Ok(__struct)
29162 }
29163 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29164 let mut __tmp = BytesMut::new(bytes);
29165 #[allow(clippy::absurd_extreme_comparisons)]
29166 #[allow(unused_comparisons)]
29167 if __tmp.remaining() < Self::ENCODED_LEN {
29168 panic!(
29169 "buffer is too small (need {} bytes, but got {})",
29170 Self::ENCODED_LEN,
29171 __tmp.remaining(),
29172 )
29173 }
29174 __tmp.put_u8(self.target_system);
29175 __tmp.put_u8(self.target_component);
29176 __tmp.put_u8(self.mission_type as u8);
29177 if matches!(version, MavlinkVersion::V2) {
29178 let len = __tmp.len();
29179 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29180 } else {
29181 __tmp.len()
29182 }
29183 }
29184}
29185#[doc = "id: 286"]
29186#[doc = "Low level message containing autopilot state relevant for a gimbal device. This message is to be sent from the autopilot to the gimbal device component. The data of this message are for the gimbal device's estimator corrections, in particular horizon compensation, as well as indicates autopilot control intentions, e.g. feed forward angular control in the z-axis."]
29187#[derive(Debug, Clone, PartialEq)]
29188#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29189#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29190pub struct AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA {
29191 #[doc = "Timestamp (time since system boot)."]
29192 pub time_boot_us: u64,
29193 #[doc = "Quaternion components of autopilot attitude: w, x, y, z (1 0 0 0 is the null-rotation, Hamilton convention)."]
29194 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
29195 pub q: [f32; 4],
29196 #[doc = "Estimated delay of the attitude data. 0 if unknown."]
29197 pub q_estimated_delay_us: u32,
29198 #[doc = "X Speed in NED (North, East, Down). NAN if unknown."]
29199 pub vx: f32,
29200 #[doc = "Y Speed in NED (North, East, Down). NAN if unknown."]
29201 pub vy: f32,
29202 #[doc = "Z Speed in NED (North, East, Down). NAN if unknown."]
29203 pub vz: f32,
29204 #[doc = "Estimated delay of the speed data. 0 if unknown."]
29205 pub v_estimated_delay_us: u32,
29206 #[doc = "Feed forward Z component of angular velocity (positive: yawing to the right). NaN to be ignored. This is to indicate if the autopilot is actively yawing."]
29207 pub feed_forward_angular_velocity_z: f32,
29208 #[doc = "Bitmap indicating which estimator outputs are valid."]
29209 pub estimator_status: EstimatorStatusFlags,
29210 #[doc = "System ID"]
29211 pub target_system: u8,
29212 #[doc = "Component ID"]
29213 pub target_component: u8,
29214 #[doc = "The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown."]
29215 pub landed_state: MavLandedState,
29216 #[doc = "Z component of angular velocity in NED (North, East, Down). NaN if unknown."]
29217 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
29218 pub angular_velocity_z: f32,
29219}
29220impl AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA {
29221 pub const ENCODED_LEN: usize = 57usize;
29222 pub const DEFAULT: Self = Self {
29223 time_boot_us: 0_u64,
29224 q: [0.0_f32; 4usize],
29225 q_estimated_delay_us: 0_u32,
29226 vx: 0.0_f32,
29227 vy: 0.0_f32,
29228 vz: 0.0_f32,
29229 v_estimated_delay_us: 0_u32,
29230 feed_forward_angular_velocity_z: 0.0_f32,
29231 estimator_status: EstimatorStatusFlags::DEFAULT,
29232 target_system: 0_u8,
29233 target_component: 0_u8,
29234 landed_state: MavLandedState::DEFAULT,
29235 angular_velocity_z: 0.0_f32,
29236 };
29237 #[cfg(feature = "arbitrary")]
29238 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29239 use arbitrary::{Arbitrary, Unstructured};
29240 let mut buf = [0u8; 1024];
29241 rng.fill_bytes(&mut buf);
29242 let mut unstructured = Unstructured::new(&buf);
29243 Self::arbitrary(&mut unstructured).unwrap_or_default()
29244 }
29245}
29246impl Default for AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA {
29247 fn default() -> Self {
29248 Self::DEFAULT.clone()
29249 }
29250}
29251impl MessageData for AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA {
29252 type Message = MavMessage;
29253 const ID: u32 = 286u32;
29254 const NAME: &'static str = "AUTOPILOT_STATE_FOR_GIMBAL_DEVICE";
29255 const EXTRA_CRC: u8 = 210u8;
29256 const ENCODED_LEN: usize = 57usize;
29257 fn deser(
29258 _version: MavlinkVersion,
29259 __input: &[u8],
29260 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29261 let avail_len = __input.len();
29262 let mut payload_buf = [0; Self::ENCODED_LEN];
29263 let mut buf = if avail_len < Self::ENCODED_LEN {
29264 payload_buf[0..avail_len].copy_from_slice(__input);
29265 Bytes::new(&payload_buf)
29266 } else {
29267 Bytes::new(__input)
29268 };
29269 let mut __struct = Self::default();
29270 __struct.time_boot_us = buf.get_u64_le();
29271 for v in &mut __struct.q {
29272 let val = buf.get_f32_le();
29273 *v = val;
29274 }
29275 __struct.q_estimated_delay_us = buf.get_u32_le();
29276 __struct.vx = buf.get_f32_le();
29277 __struct.vy = buf.get_f32_le();
29278 __struct.vz = buf.get_f32_le();
29279 __struct.v_estimated_delay_us = buf.get_u32_le();
29280 __struct.feed_forward_angular_velocity_z = buf.get_f32_le();
29281 let tmp = buf.get_u16_le();
29282 __struct.estimator_status = EstimatorStatusFlags::from_bits(
29283 tmp & EstimatorStatusFlags::all().bits(),
29284 )
29285 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
29286 flag_type: "EstimatorStatusFlags",
29287 value: tmp as u32,
29288 })?;
29289 __struct.target_system = buf.get_u8();
29290 __struct.target_component = buf.get_u8();
29291 let tmp = buf.get_u8();
29292 __struct.landed_state =
29293 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
29294 enum_type: "MavLandedState",
29295 value: tmp as u32,
29296 })?;
29297 __struct.angular_velocity_z = buf.get_f32_le();
29298 Ok(__struct)
29299 }
29300 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29301 let mut __tmp = BytesMut::new(bytes);
29302 #[allow(clippy::absurd_extreme_comparisons)]
29303 #[allow(unused_comparisons)]
29304 if __tmp.remaining() < Self::ENCODED_LEN {
29305 panic!(
29306 "buffer is too small (need {} bytes, but got {})",
29307 Self::ENCODED_LEN,
29308 __tmp.remaining(),
29309 )
29310 }
29311 __tmp.put_u64_le(self.time_boot_us);
29312 for val in &self.q {
29313 __tmp.put_f32_le(*val);
29314 }
29315 __tmp.put_u32_le(self.q_estimated_delay_us);
29316 __tmp.put_f32_le(self.vx);
29317 __tmp.put_f32_le(self.vy);
29318 __tmp.put_f32_le(self.vz);
29319 __tmp.put_u32_le(self.v_estimated_delay_us);
29320 __tmp.put_f32_le(self.feed_forward_angular_velocity_z);
29321 __tmp.put_u16_le(self.estimator_status.bits());
29322 __tmp.put_u8(self.target_system);
29323 __tmp.put_u8(self.target_component);
29324 __tmp.put_u8(self.landed_state as u8);
29325 __tmp.put_f32_le(self.angular_velocity_z);
29326 if matches!(version, MavlinkVersion::V2) {
29327 let len = __tmp.len();
29328 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29329 } else {
29330 __tmp.len()
29331 }
29332 }
29333}
29334#[doc = "id: 267"]
29335#[doc = "A message containing logged data which requires a LOGGING_ACK to be sent back."]
29336#[derive(Debug, Clone, PartialEq)]
29337#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29338#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29339pub struct LOGGING_DATA_ACKED_DATA {
29340 #[doc = "sequence number (can wrap)"]
29341 pub sequence: u16,
29342 #[doc = "system ID of the target"]
29343 pub target_system: u8,
29344 #[doc = "component ID of the target"]
29345 pub target_component: u8,
29346 #[doc = "data length"]
29347 pub length: u8,
29348 #[doc = "offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to UINT8_MAX if no start exists)."]
29349 pub first_message_offset: u8,
29350 #[doc = "logged data"]
29351 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
29352 pub data: [u8; 249],
29353}
29354impl LOGGING_DATA_ACKED_DATA {
29355 pub const ENCODED_LEN: usize = 255usize;
29356 pub const DEFAULT: Self = Self {
29357 sequence: 0_u16,
29358 target_system: 0_u8,
29359 target_component: 0_u8,
29360 length: 0_u8,
29361 first_message_offset: 0_u8,
29362 data: [0_u8; 249usize],
29363 };
29364 #[cfg(feature = "arbitrary")]
29365 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29366 use arbitrary::{Arbitrary, Unstructured};
29367 let mut buf = [0u8; 1024];
29368 rng.fill_bytes(&mut buf);
29369 let mut unstructured = Unstructured::new(&buf);
29370 Self::arbitrary(&mut unstructured).unwrap_or_default()
29371 }
29372}
29373impl Default for LOGGING_DATA_ACKED_DATA {
29374 fn default() -> Self {
29375 Self::DEFAULT.clone()
29376 }
29377}
29378impl MessageData for LOGGING_DATA_ACKED_DATA {
29379 type Message = MavMessage;
29380 const ID: u32 = 267u32;
29381 const NAME: &'static str = "LOGGING_DATA_ACKED";
29382 const EXTRA_CRC: u8 = 35u8;
29383 const ENCODED_LEN: usize = 255usize;
29384 fn deser(
29385 _version: MavlinkVersion,
29386 __input: &[u8],
29387 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29388 let avail_len = __input.len();
29389 let mut payload_buf = [0; Self::ENCODED_LEN];
29390 let mut buf = if avail_len < Self::ENCODED_LEN {
29391 payload_buf[0..avail_len].copy_from_slice(__input);
29392 Bytes::new(&payload_buf)
29393 } else {
29394 Bytes::new(__input)
29395 };
29396 let mut __struct = Self::default();
29397 __struct.sequence = buf.get_u16_le();
29398 __struct.target_system = buf.get_u8();
29399 __struct.target_component = buf.get_u8();
29400 __struct.length = buf.get_u8();
29401 __struct.first_message_offset = buf.get_u8();
29402 for v in &mut __struct.data {
29403 let val = buf.get_u8();
29404 *v = val;
29405 }
29406 Ok(__struct)
29407 }
29408 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29409 let mut __tmp = BytesMut::new(bytes);
29410 #[allow(clippy::absurd_extreme_comparisons)]
29411 #[allow(unused_comparisons)]
29412 if __tmp.remaining() < Self::ENCODED_LEN {
29413 panic!(
29414 "buffer is too small (need {} bytes, but got {})",
29415 Self::ENCODED_LEN,
29416 __tmp.remaining(),
29417 )
29418 }
29419 __tmp.put_u16_le(self.sequence);
29420 __tmp.put_u8(self.target_system);
29421 __tmp.put_u8(self.target_component);
29422 __tmp.put_u8(self.length);
29423 __tmp.put_u8(self.first_message_offset);
29424 for val in &self.data {
29425 __tmp.put_u8(*val);
29426 }
29427 if matches!(version, MavlinkVersion::V2) {
29428 let len = __tmp.len();
29429 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29430 } else {
29431 __tmp.len()
29432 }
29433 }
29434}
29435#[doc = "id: 413"]
29436#[doc = "Response to a REQUEST_EVENT in case of an error (e.g. the event is not available anymore)."]
29437#[derive(Debug, Clone, PartialEq)]
29438#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29439#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29440pub struct RESPONSE_EVENT_ERROR_DATA {
29441 #[doc = "Sequence number."]
29442 pub sequence: u16,
29443 #[doc = "Oldest Sequence number that is still available after the sequence set in REQUEST_EVENT."]
29444 pub sequence_oldest_available: u16,
29445 #[doc = "System ID"]
29446 pub target_system: u8,
29447 #[doc = "Component ID"]
29448 pub target_component: u8,
29449 #[doc = "Error reason."]
29450 pub reason: MavEventErrorReason,
29451}
29452impl RESPONSE_EVENT_ERROR_DATA {
29453 pub const ENCODED_LEN: usize = 7usize;
29454 pub const DEFAULT: Self = Self {
29455 sequence: 0_u16,
29456 sequence_oldest_available: 0_u16,
29457 target_system: 0_u8,
29458 target_component: 0_u8,
29459 reason: MavEventErrorReason::DEFAULT,
29460 };
29461 #[cfg(feature = "arbitrary")]
29462 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29463 use arbitrary::{Arbitrary, Unstructured};
29464 let mut buf = [0u8; 1024];
29465 rng.fill_bytes(&mut buf);
29466 let mut unstructured = Unstructured::new(&buf);
29467 Self::arbitrary(&mut unstructured).unwrap_or_default()
29468 }
29469}
29470impl Default for RESPONSE_EVENT_ERROR_DATA {
29471 fn default() -> Self {
29472 Self::DEFAULT.clone()
29473 }
29474}
29475impl MessageData for RESPONSE_EVENT_ERROR_DATA {
29476 type Message = MavMessage;
29477 const ID: u32 = 413u32;
29478 const NAME: &'static str = "RESPONSE_EVENT_ERROR";
29479 const EXTRA_CRC: u8 = 77u8;
29480 const ENCODED_LEN: usize = 7usize;
29481 fn deser(
29482 _version: MavlinkVersion,
29483 __input: &[u8],
29484 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29485 let avail_len = __input.len();
29486 let mut payload_buf = [0; Self::ENCODED_LEN];
29487 let mut buf = if avail_len < Self::ENCODED_LEN {
29488 payload_buf[0..avail_len].copy_from_slice(__input);
29489 Bytes::new(&payload_buf)
29490 } else {
29491 Bytes::new(__input)
29492 };
29493 let mut __struct = Self::default();
29494 __struct.sequence = buf.get_u16_le();
29495 __struct.sequence_oldest_available = buf.get_u16_le();
29496 __struct.target_system = buf.get_u8();
29497 __struct.target_component = buf.get_u8();
29498 let tmp = buf.get_u8();
29499 __struct.reason =
29500 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
29501 enum_type: "MavEventErrorReason",
29502 value: tmp as u32,
29503 })?;
29504 Ok(__struct)
29505 }
29506 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29507 let mut __tmp = BytesMut::new(bytes);
29508 #[allow(clippy::absurd_extreme_comparisons)]
29509 #[allow(unused_comparisons)]
29510 if __tmp.remaining() < Self::ENCODED_LEN {
29511 panic!(
29512 "buffer is too small (need {} bytes, but got {})",
29513 Self::ENCODED_LEN,
29514 __tmp.remaining(),
29515 )
29516 }
29517 __tmp.put_u16_le(self.sequence);
29518 __tmp.put_u16_le(self.sequence_oldest_available);
29519 __tmp.put_u8(self.target_system);
29520 __tmp.put_u8(self.target_component);
29521 __tmp.put_u8(self.reason as u8);
29522 if matches!(version, MavlinkVersion::V2) {
29523 let len = __tmp.len();
29524 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29525 } else {
29526 __tmp.len()
29527 }
29528 }
29529}
29530#[doc = "id: 143"]
29531#[doc = "Barometer readings for 3rd barometer."]
29532#[derive(Debug, Clone, PartialEq)]
29533#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29534#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29535pub struct SCALED_PRESSURE3_DATA {
29536 #[doc = "Timestamp (time since system boot)."]
29537 pub time_boot_ms: u32,
29538 #[doc = "Absolute pressure"]
29539 pub press_abs: f32,
29540 #[doc = "Differential pressure"]
29541 pub press_diff: f32,
29542 #[doc = "Absolute pressure temperature"]
29543 pub temperature: i16,
29544 #[doc = "Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC."]
29545 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
29546 pub temperature_press_diff: i16,
29547}
29548impl SCALED_PRESSURE3_DATA {
29549 pub const ENCODED_LEN: usize = 16usize;
29550 pub const DEFAULT: Self = Self {
29551 time_boot_ms: 0_u32,
29552 press_abs: 0.0_f32,
29553 press_diff: 0.0_f32,
29554 temperature: 0_i16,
29555 temperature_press_diff: 0_i16,
29556 };
29557 #[cfg(feature = "arbitrary")]
29558 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29559 use arbitrary::{Arbitrary, Unstructured};
29560 let mut buf = [0u8; 1024];
29561 rng.fill_bytes(&mut buf);
29562 let mut unstructured = Unstructured::new(&buf);
29563 Self::arbitrary(&mut unstructured).unwrap_or_default()
29564 }
29565}
29566impl Default for SCALED_PRESSURE3_DATA {
29567 fn default() -> Self {
29568 Self::DEFAULT.clone()
29569 }
29570}
29571impl MessageData for SCALED_PRESSURE3_DATA {
29572 type Message = MavMessage;
29573 const ID: u32 = 143u32;
29574 const NAME: &'static str = "SCALED_PRESSURE3";
29575 const EXTRA_CRC: u8 = 131u8;
29576 const ENCODED_LEN: usize = 16usize;
29577 fn deser(
29578 _version: MavlinkVersion,
29579 __input: &[u8],
29580 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29581 let avail_len = __input.len();
29582 let mut payload_buf = [0; Self::ENCODED_LEN];
29583 let mut buf = if avail_len < Self::ENCODED_LEN {
29584 payload_buf[0..avail_len].copy_from_slice(__input);
29585 Bytes::new(&payload_buf)
29586 } else {
29587 Bytes::new(__input)
29588 };
29589 let mut __struct = Self::default();
29590 __struct.time_boot_ms = buf.get_u32_le();
29591 __struct.press_abs = buf.get_f32_le();
29592 __struct.press_diff = buf.get_f32_le();
29593 __struct.temperature = buf.get_i16_le();
29594 __struct.temperature_press_diff = buf.get_i16_le();
29595 Ok(__struct)
29596 }
29597 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29598 let mut __tmp = BytesMut::new(bytes);
29599 #[allow(clippy::absurd_extreme_comparisons)]
29600 #[allow(unused_comparisons)]
29601 if __tmp.remaining() < Self::ENCODED_LEN {
29602 panic!(
29603 "buffer is too small (need {} bytes, but got {})",
29604 Self::ENCODED_LEN,
29605 __tmp.remaining(),
29606 )
29607 }
29608 __tmp.put_u32_le(self.time_boot_ms);
29609 __tmp.put_f32_le(self.press_abs);
29610 __tmp.put_f32_le(self.press_diff);
29611 __tmp.put_i16_le(self.temperature);
29612 __tmp.put_i16_le(self.temperature_press_diff);
29613 if matches!(version, MavlinkVersion::V2) {
29614 let len = __tmp.len();
29615 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29616 } else {
29617 __tmp.len()
29618 }
29619 }
29620}
29621#[doc = "id: 387"]
29622#[doc = "A forwarded CANFD frame as requested by MAV_CMD_CAN_FORWARD. These are separated from CAN_FRAME as they need different handling (eg. TAO handling)."]
29623#[derive(Debug, Clone, PartialEq)]
29624#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29625#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29626pub struct CANFD_FRAME_DATA {
29627 #[doc = "Frame ID"]
29628 pub id: u32,
29629 #[doc = "System ID."]
29630 pub target_system: u8,
29631 #[doc = "Component ID."]
29632 pub target_component: u8,
29633 #[doc = "bus number"]
29634 pub bus: u8,
29635 #[doc = "Frame length"]
29636 pub len: u8,
29637 #[doc = "Frame data"]
29638 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
29639 pub data: [u8; 64],
29640}
29641impl CANFD_FRAME_DATA {
29642 pub const ENCODED_LEN: usize = 72usize;
29643 pub const DEFAULT: Self = Self {
29644 id: 0_u32,
29645 target_system: 0_u8,
29646 target_component: 0_u8,
29647 bus: 0_u8,
29648 len: 0_u8,
29649 data: [0_u8; 64usize],
29650 };
29651 #[cfg(feature = "arbitrary")]
29652 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29653 use arbitrary::{Arbitrary, Unstructured};
29654 let mut buf = [0u8; 1024];
29655 rng.fill_bytes(&mut buf);
29656 let mut unstructured = Unstructured::new(&buf);
29657 Self::arbitrary(&mut unstructured).unwrap_or_default()
29658 }
29659}
29660impl Default for CANFD_FRAME_DATA {
29661 fn default() -> Self {
29662 Self::DEFAULT.clone()
29663 }
29664}
29665impl MessageData for CANFD_FRAME_DATA {
29666 type Message = MavMessage;
29667 const ID: u32 = 387u32;
29668 const NAME: &'static str = "CANFD_FRAME";
29669 const EXTRA_CRC: u8 = 4u8;
29670 const ENCODED_LEN: usize = 72usize;
29671 fn deser(
29672 _version: MavlinkVersion,
29673 __input: &[u8],
29674 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29675 let avail_len = __input.len();
29676 let mut payload_buf = [0; Self::ENCODED_LEN];
29677 let mut buf = if avail_len < Self::ENCODED_LEN {
29678 payload_buf[0..avail_len].copy_from_slice(__input);
29679 Bytes::new(&payload_buf)
29680 } else {
29681 Bytes::new(__input)
29682 };
29683 let mut __struct = Self::default();
29684 __struct.id = buf.get_u32_le();
29685 __struct.target_system = buf.get_u8();
29686 __struct.target_component = buf.get_u8();
29687 __struct.bus = buf.get_u8();
29688 __struct.len = buf.get_u8();
29689 for v in &mut __struct.data {
29690 let val = buf.get_u8();
29691 *v = val;
29692 }
29693 Ok(__struct)
29694 }
29695 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29696 let mut __tmp = BytesMut::new(bytes);
29697 #[allow(clippy::absurd_extreme_comparisons)]
29698 #[allow(unused_comparisons)]
29699 if __tmp.remaining() < Self::ENCODED_LEN {
29700 panic!(
29701 "buffer is too small (need {} bytes, but got {})",
29702 Self::ENCODED_LEN,
29703 __tmp.remaining(),
29704 )
29705 }
29706 __tmp.put_u32_le(self.id);
29707 __tmp.put_u8(self.target_system);
29708 __tmp.put_u8(self.target_component);
29709 __tmp.put_u8(self.bus);
29710 __tmp.put_u8(self.len);
29711 for val in &self.data {
29712 __tmp.put_u8(*val);
29713 }
29714 if matches!(version, MavlinkVersion::V2) {
29715 let len = __tmp.len();
29716 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29717 } else {
29718 __tmp.len()
29719 }
29720 }
29721}
29722#[doc = "id: 51"]
29723#[doc = "Request the information of the mission item with the sequence number seq. The response of the system to this message should be a MISSION_ITEM_INT message. <https://mavlink.io/en/services/mission.html>."]
29724#[derive(Debug, Clone, PartialEq)]
29725#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29726#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29727pub struct MISSION_REQUEST_INT_DATA {
29728 #[doc = "Sequence"]
29729 pub seq: u16,
29730 #[doc = "System ID"]
29731 pub target_system: u8,
29732 #[doc = "Component ID"]
29733 pub target_component: u8,
29734 #[doc = "Mission type."]
29735 #[cfg_attr(feature = "serde", serde(default))]
29736 pub mission_type: MavMissionType,
29737}
29738impl MISSION_REQUEST_INT_DATA {
29739 pub const ENCODED_LEN: usize = 5usize;
29740 pub const DEFAULT: Self = Self {
29741 seq: 0_u16,
29742 target_system: 0_u8,
29743 target_component: 0_u8,
29744 mission_type: MavMissionType::DEFAULT,
29745 };
29746 #[cfg(feature = "arbitrary")]
29747 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29748 use arbitrary::{Arbitrary, Unstructured};
29749 let mut buf = [0u8; 1024];
29750 rng.fill_bytes(&mut buf);
29751 let mut unstructured = Unstructured::new(&buf);
29752 Self::arbitrary(&mut unstructured).unwrap_or_default()
29753 }
29754}
29755impl Default for MISSION_REQUEST_INT_DATA {
29756 fn default() -> Self {
29757 Self::DEFAULT.clone()
29758 }
29759}
29760impl MessageData for MISSION_REQUEST_INT_DATA {
29761 type Message = MavMessage;
29762 const ID: u32 = 51u32;
29763 const NAME: &'static str = "MISSION_REQUEST_INT";
29764 const EXTRA_CRC: u8 = 196u8;
29765 const ENCODED_LEN: usize = 5usize;
29766 fn deser(
29767 _version: MavlinkVersion,
29768 __input: &[u8],
29769 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29770 let avail_len = __input.len();
29771 let mut payload_buf = [0; Self::ENCODED_LEN];
29772 let mut buf = if avail_len < Self::ENCODED_LEN {
29773 payload_buf[0..avail_len].copy_from_slice(__input);
29774 Bytes::new(&payload_buf)
29775 } else {
29776 Bytes::new(__input)
29777 };
29778 let mut __struct = Self::default();
29779 __struct.seq = buf.get_u16_le();
29780 __struct.target_system = buf.get_u8();
29781 __struct.target_component = buf.get_u8();
29782 let tmp = buf.get_u8();
29783 __struct.mission_type =
29784 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
29785 enum_type: "MavMissionType",
29786 value: tmp as u32,
29787 })?;
29788 Ok(__struct)
29789 }
29790 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29791 let mut __tmp = BytesMut::new(bytes);
29792 #[allow(clippy::absurd_extreme_comparisons)]
29793 #[allow(unused_comparisons)]
29794 if __tmp.remaining() < Self::ENCODED_LEN {
29795 panic!(
29796 "buffer is too small (need {} bytes, but got {})",
29797 Self::ENCODED_LEN,
29798 __tmp.remaining(),
29799 )
29800 }
29801 __tmp.put_u16_le(self.seq);
29802 __tmp.put_u8(self.target_system);
29803 __tmp.put_u8(self.target_component);
29804 __tmp.put_u8(self.mission_type as u8);
29805 if matches!(version, MavlinkVersion::V2) {
29806 let len = __tmp.len();
29807 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29808 } else {
29809 __tmp.len()
29810 }
29811 }
29812}
29813#[doc = "id: 192"]
29814#[doc = "Reports results of completed compass calibration. Sent until MAG_CAL_ACK received."]
29815#[derive(Debug, Clone, PartialEq)]
29816#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29817#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29818pub struct MAG_CAL_REPORT_DATA {
29819 #[doc = "RMS milligauss residuals."]
29820 pub fitness: f32,
29821 #[doc = "X offset."]
29822 pub ofs_x: f32,
29823 #[doc = "Y offset."]
29824 pub ofs_y: f32,
29825 #[doc = "Z offset."]
29826 pub ofs_z: f32,
29827 #[doc = "X diagonal (matrix 11)."]
29828 pub diag_x: f32,
29829 #[doc = "Y diagonal (matrix 22)."]
29830 pub diag_y: f32,
29831 #[doc = "Z diagonal (matrix 33)."]
29832 pub diag_z: f32,
29833 #[doc = "X off-diagonal (matrix 12 and 21)."]
29834 pub offdiag_x: f32,
29835 #[doc = "Y off-diagonal (matrix 13 and 31)."]
29836 pub offdiag_y: f32,
29837 #[doc = "Z off-diagonal (matrix 32 and 23)."]
29838 pub offdiag_z: f32,
29839 #[doc = "Compass being calibrated."]
29840 pub compass_id: u8,
29841 #[doc = "Bitmask of compasses being calibrated."]
29842 pub cal_mask: u8,
29843 #[doc = "Calibration Status."]
29844 pub cal_status: MagCalStatus,
29845 #[doc = "0=requires a MAV_CMD_DO_ACCEPT_MAG_CAL, 1=saved to parameters."]
29846 pub autosaved: u8,
29847 #[doc = "Confidence in orientation (higher is better)."]
29848 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
29849 pub orientation_confidence: f32,
29850 #[doc = "orientation before calibration."]
29851 #[cfg_attr(feature = "serde", serde(default))]
29852 pub old_orientation: MavSensorOrientation,
29853 #[doc = "orientation after calibration."]
29854 #[cfg_attr(feature = "serde", serde(default))]
29855 pub new_orientation: MavSensorOrientation,
29856 #[doc = "field radius correction factor"]
29857 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
29858 pub scale_factor: f32,
29859}
29860impl MAG_CAL_REPORT_DATA {
29861 pub const ENCODED_LEN: usize = 54usize;
29862 pub const DEFAULT: Self = Self {
29863 fitness: 0.0_f32,
29864 ofs_x: 0.0_f32,
29865 ofs_y: 0.0_f32,
29866 ofs_z: 0.0_f32,
29867 diag_x: 0.0_f32,
29868 diag_y: 0.0_f32,
29869 diag_z: 0.0_f32,
29870 offdiag_x: 0.0_f32,
29871 offdiag_y: 0.0_f32,
29872 offdiag_z: 0.0_f32,
29873 compass_id: 0_u8,
29874 cal_mask: 0_u8,
29875 cal_status: MagCalStatus::DEFAULT,
29876 autosaved: 0_u8,
29877 orientation_confidence: 0.0_f32,
29878 old_orientation: MavSensorOrientation::DEFAULT,
29879 new_orientation: MavSensorOrientation::DEFAULT,
29880 scale_factor: 0.0_f32,
29881 };
29882 #[cfg(feature = "arbitrary")]
29883 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29884 use arbitrary::{Arbitrary, Unstructured};
29885 let mut buf = [0u8; 1024];
29886 rng.fill_bytes(&mut buf);
29887 let mut unstructured = Unstructured::new(&buf);
29888 Self::arbitrary(&mut unstructured).unwrap_or_default()
29889 }
29890}
29891impl Default for MAG_CAL_REPORT_DATA {
29892 fn default() -> Self {
29893 Self::DEFAULT.clone()
29894 }
29895}
29896impl MessageData for MAG_CAL_REPORT_DATA {
29897 type Message = MavMessage;
29898 const ID: u32 = 192u32;
29899 const NAME: &'static str = "MAG_CAL_REPORT";
29900 const EXTRA_CRC: u8 = 36u8;
29901 const ENCODED_LEN: usize = 54usize;
29902 fn deser(
29903 _version: MavlinkVersion,
29904 __input: &[u8],
29905 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29906 let avail_len = __input.len();
29907 let mut payload_buf = [0; Self::ENCODED_LEN];
29908 let mut buf = if avail_len < Self::ENCODED_LEN {
29909 payload_buf[0..avail_len].copy_from_slice(__input);
29910 Bytes::new(&payload_buf)
29911 } else {
29912 Bytes::new(__input)
29913 };
29914 let mut __struct = Self::default();
29915 __struct.fitness = buf.get_f32_le();
29916 __struct.ofs_x = buf.get_f32_le();
29917 __struct.ofs_y = buf.get_f32_le();
29918 __struct.ofs_z = buf.get_f32_le();
29919 __struct.diag_x = buf.get_f32_le();
29920 __struct.diag_y = buf.get_f32_le();
29921 __struct.diag_z = buf.get_f32_le();
29922 __struct.offdiag_x = buf.get_f32_le();
29923 __struct.offdiag_y = buf.get_f32_le();
29924 __struct.offdiag_z = buf.get_f32_le();
29925 __struct.compass_id = buf.get_u8();
29926 __struct.cal_mask = buf.get_u8();
29927 let tmp = buf.get_u8();
29928 __struct.cal_status =
29929 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
29930 enum_type: "MagCalStatus",
29931 value: tmp as u32,
29932 })?;
29933 __struct.autosaved = buf.get_u8();
29934 __struct.orientation_confidence = buf.get_f32_le();
29935 let tmp = buf.get_u8();
29936 __struct.old_orientation =
29937 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
29938 enum_type: "MavSensorOrientation",
29939 value: tmp as u32,
29940 })?;
29941 let tmp = buf.get_u8();
29942 __struct.new_orientation =
29943 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
29944 enum_type: "MavSensorOrientation",
29945 value: tmp as u32,
29946 })?;
29947 __struct.scale_factor = buf.get_f32_le();
29948 Ok(__struct)
29949 }
29950 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29951 let mut __tmp = BytesMut::new(bytes);
29952 #[allow(clippy::absurd_extreme_comparisons)]
29953 #[allow(unused_comparisons)]
29954 if __tmp.remaining() < Self::ENCODED_LEN {
29955 panic!(
29956 "buffer is too small (need {} bytes, but got {})",
29957 Self::ENCODED_LEN,
29958 __tmp.remaining(),
29959 )
29960 }
29961 __tmp.put_f32_le(self.fitness);
29962 __tmp.put_f32_le(self.ofs_x);
29963 __tmp.put_f32_le(self.ofs_y);
29964 __tmp.put_f32_le(self.ofs_z);
29965 __tmp.put_f32_le(self.diag_x);
29966 __tmp.put_f32_le(self.diag_y);
29967 __tmp.put_f32_le(self.diag_z);
29968 __tmp.put_f32_le(self.offdiag_x);
29969 __tmp.put_f32_le(self.offdiag_y);
29970 __tmp.put_f32_le(self.offdiag_z);
29971 __tmp.put_u8(self.compass_id);
29972 __tmp.put_u8(self.cal_mask);
29973 __tmp.put_u8(self.cal_status as u8);
29974 __tmp.put_u8(self.autosaved);
29975 __tmp.put_f32_le(self.orientation_confidence);
29976 __tmp.put_u8(self.old_orientation as u8);
29977 __tmp.put_u8(self.new_orientation as u8);
29978 __tmp.put_f32_le(self.scale_factor);
29979 if matches!(version, MavlinkVersion::V2) {
29980 let len = __tmp.len();
29981 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29982 } else {
29983 __tmp.len()
29984 }
29985 }
29986}
29987#[doc = "id: 77"]
29988#[doc = "Report status of a command. Includes feedback whether the command was executed. The command microservice is documented at <https://mavlink.io/en/services/command.html>."]
29989#[derive(Debug, Clone, PartialEq)]
29990#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29991#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29992pub struct COMMAND_ACK_DATA {
29993 #[doc = "Command ID (of acknowledged command)."]
29994 pub command: MavCmd,
29995 #[doc = "Result of command."]
29996 pub result: MavResult,
29997 #[doc = "The progress percentage when result is MAV_RESULT_IN_PROGRESS. Values: [0-100], or UINT8_MAX if the progress is unknown."]
29998 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
29999 pub progress: u8,
30000 #[doc = "Additional result information. Can be set with a command-specific enum containing command-specific error reasons for why the command might be denied. If used, the associated enum must be documented in the corresponding MAV_CMD (this enum should have a 0 value to indicate \"unused\" or \"unknown\")."]
30001 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
30002 pub result_param2: i32,
30003 #[doc = "System ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement."]
30004 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
30005 pub target_system: u8,
30006 #[doc = "Component ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement."]
30007 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
30008 pub target_component: u8,
30009}
30010impl COMMAND_ACK_DATA {
30011 pub const ENCODED_LEN: usize = 10usize;
30012 pub const DEFAULT: Self = Self {
30013 command: MavCmd::DEFAULT,
30014 result: MavResult::DEFAULT,
30015 progress: 0_u8,
30016 result_param2: 0_i32,
30017 target_system: 0_u8,
30018 target_component: 0_u8,
30019 };
30020 #[cfg(feature = "arbitrary")]
30021 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
30022 use arbitrary::{Arbitrary, Unstructured};
30023 let mut buf = [0u8; 1024];
30024 rng.fill_bytes(&mut buf);
30025 let mut unstructured = Unstructured::new(&buf);
30026 Self::arbitrary(&mut unstructured).unwrap_or_default()
30027 }
30028}
30029impl Default for COMMAND_ACK_DATA {
30030 fn default() -> Self {
30031 Self::DEFAULT.clone()
30032 }
30033}
30034impl MessageData for COMMAND_ACK_DATA {
30035 type Message = MavMessage;
30036 const ID: u32 = 77u32;
30037 const NAME: &'static str = "COMMAND_ACK";
30038 const EXTRA_CRC: u8 = 143u8;
30039 const ENCODED_LEN: usize = 10usize;
30040 fn deser(
30041 _version: MavlinkVersion,
30042 __input: &[u8],
30043 ) -> Result<Self, ::mavlink_core::error::ParserError> {
30044 let avail_len = __input.len();
30045 let mut payload_buf = [0; Self::ENCODED_LEN];
30046 let mut buf = if avail_len < Self::ENCODED_LEN {
30047 payload_buf[0..avail_len].copy_from_slice(__input);
30048 Bytes::new(&payload_buf)
30049 } else {
30050 Bytes::new(__input)
30051 };
30052 let mut __struct = Self::default();
30053 let tmp = buf.get_u16_le();
30054 __struct.command = FromPrimitive::from_u16(tmp).ok_or(
30055 ::mavlink_core::error::ParserError::InvalidEnum {
30056 enum_type: "MavCmd",
30057 value: tmp as u32,
30058 },
30059 )?;
30060 let tmp = buf.get_u8();
30061 __struct.result =
30062 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
30063 enum_type: "MavResult",
30064 value: tmp as u32,
30065 })?;
30066 __struct.progress = buf.get_u8();
30067 __struct.result_param2 = buf.get_i32_le();
30068 __struct.target_system = buf.get_u8();
30069 __struct.target_component = buf.get_u8();
30070 Ok(__struct)
30071 }
30072 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
30073 let mut __tmp = BytesMut::new(bytes);
30074 #[allow(clippy::absurd_extreme_comparisons)]
30075 #[allow(unused_comparisons)]
30076 if __tmp.remaining() < Self::ENCODED_LEN {
30077 panic!(
30078 "buffer is too small (need {} bytes, but got {})",
30079 Self::ENCODED_LEN,
30080 __tmp.remaining(),
30081 )
30082 }
30083 __tmp.put_u16_le(self.command as u16);
30084 __tmp.put_u8(self.result as u8);
30085 __tmp.put_u8(self.progress);
30086 __tmp.put_i32_le(self.result_param2);
30087 __tmp.put_u8(self.target_system);
30088 __tmp.put_u8(self.target_component);
30089 if matches!(version, MavlinkVersion::V2) {
30090 let len = __tmp.len();
30091 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
30092 } else {
30093 __tmp.len()
30094 }
30095 }
30096}
30097#[doc = "id: 46"]
30098#[doc = "A certain mission item has been reached. The system will either hold this position (or circle on the orbit) or (if the autocontinue on the WP was set) continue to the next waypoint."]
30099#[derive(Debug, Clone, PartialEq)]
30100#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
30101#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
30102pub struct MISSION_ITEM_REACHED_DATA {
30103 #[doc = "Sequence"]
30104 pub seq: u16,
30105}
30106impl MISSION_ITEM_REACHED_DATA {
30107 pub const ENCODED_LEN: usize = 2usize;
30108 pub const DEFAULT: Self = Self { seq: 0_u16 };
30109 #[cfg(feature = "arbitrary")]
30110 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
30111 use arbitrary::{Arbitrary, Unstructured};
30112 let mut buf = [0u8; 1024];
30113 rng.fill_bytes(&mut buf);
30114 let mut unstructured = Unstructured::new(&buf);
30115 Self::arbitrary(&mut unstructured).unwrap_or_default()
30116 }
30117}
30118impl Default for MISSION_ITEM_REACHED_DATA {
30119 fn default() -> Self {
30120 Self::DEFAULT.clone()
30121 }
30122}
30123impl MessageData for MISSION_ITEM_REACHED_DATA {
30124 type Message = MavMessage;
30125 const ID: u32 = 46u32;
30126 const NAME: &'static str = "MISSION_ITEM_REACHED";
30127 const EXTRA_CRC: u8 = 11u8;
30128 const ENCODED_LEN: usize = 2usize;
30129 fn deser(
30130 _version: MavlinkVersion,
30131 __input: &[u8],
30132 ) -> Result<Self, ::mavlink_core::error::ParserError> {
30133 let avail_len = __input.len();
30134 let mut payload_buf = [0; Self::ENCODED_LEN];
30135 let mut buf = if avail_len < Self::ENCODED_LEN {
30136 payload_buf[0..avail_len].copy_from_slice(__input);
30137 Bytes::new(&payload_buf)
30138 } else {
30139 Bytes::new(__input)
30140 };
30141 let mut __struct = Self::default();
30142 __struct.seq = buf.get_u16_le();
30143 Ok(__struct)
30144 }
30145 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
30146 let mut __tmp = BytesMut::new(bytes);
30147 #[allow(clippy::absurd_extreme_comparisons)]
30148 #[allow(unused_comparisons)]
30149 if __tmp.remaining() < Self::ENCODED_LEN {
30150 panic!(
30151 "buffer is too small (need {} bytes, but got {})",
30152 Self::ENCODED_LEN,
30153 __tmp.remaining(),
30154 )
30155 }
30156 __tmp.put_u16_le(self.seq);
30157 if matches!(version, MavlinkVersion::V2) {
30158 let len = __tmp.len();
30159 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
30160 } else {
30161 __tmp.len()
30162 }
30163 }
30164}
30165#[doc = "id: 6"]
30166#[doc = "Accept / deny control of this MAV."]
30167#[derive(Debug, Clone, PartialEq)]
30168#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
30169#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
30170pub struct CHANGE_OPERATOR_CONTROL_ACK_DATA {
30171 #[doc = "ID of the GCS this message"]
30172 pub gcs_system_id: u8,
30173 #[doc = "0: request control of this MAV, 1: Release control of this MAV"]
30174 pub control_request: u8,
30175 #[doc = "0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control"]
30176 pub ack: u8,
30177}
30178impl CHANGE_OPERATOR_CONTROL_ACK_DATA {
30179 pub const ENCODED_LEN: usize = 3usize;
30180 pub const DEFAULT: Self = Self {
30181 gcs_system_id: 0_u8,
30182 control_request: 0_u8,
30183 ack: 0_u8,
30184 };
30185 #[cfg(feature = "arbitrary")]
30186 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
30187 use arbitrary::{Arbitrary, Unstructured};
30188 let mut buf = [0u8; 1024];
30189 rng.fill_bytes(&mut buf);
30190 let mut unstructured = Unstructured::new(&buf);
30191 Self::arbitrary(&mut unstructured).unwrap_or_default()
30192 }
30193}
30194impl Default for CHANGE_OPERATOR_CONTROL_ACK_DATA {
30195 fn default() -> Self {
30196 Self::DEFAULT.clone()
30197 }
30198}
30199impl MessageData for CHANGE_OPERATOR_CONTROL_ACK_DATA {
30200 type Message = MavMessage;
30201 const ID: u32 = 6u32;
30202 const NAME: &'static str = "CHANGE_OPERATOR_CONTROL_ACK";
30203 const EXTRA_CRC: u8 = 104u8;
30204 const ENCODED_LEN: usize = 3usize;
30205 fn deser(
30206 _version: MavlinkVersion,
30207 __input: &[u8],
30208 ) -> Result<Self, ::mavlink_core::error::ParserError> {
30209 let avail_len = __input.len();
30210 let mut payload_buf = [0; Self::ENCODED_LEN];
30211 let mut buf = if avail_len < Self::ENCODED_LEN {
30212 payload_buf[0..avail_len].copy_from_slice(__input);
30213 Bytes::new(&payload_buf)
30214 } else {
30215 Bytes::new(__input)
30216 };
30217 let mut __struct = Self::default();
30218 __struct.gcs_system_id = buf.get_u8();
30219 __struct.control_request = buf.get_u8();
30220 __struct.ack = buf.get_u8();
30221 Ok(__struct)
30222 }
30223 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
30224 let mut __tmp = BytesMut::new(bytes);
30225 #[allow(clippy::absurd_extreme_comparisons)]
30226 #[allow(unused_comparisons)]
30227 if __tmp.remaining() < Self::ENCODED_LEN {
30228 panic!(
30229 "buffer is too small (need {} bytes, but got {})",
30230 Self::ENCODED_LEN,
30231 __tmp.remaining(),
30232 )
30233 }
30234 __tmp.put_u8(self.gcs_system_id);
30235 __tmp.put_u8(self.control_request);
30236 __tmp.put_u8(self.ack);
30237 if matches!(version, MavlinkVersion::V2) {
30238 let len = __tmp.len();
30239 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
30240 } else {
30241 __tmp.len()
30242 }
30243 }
30244}
30245#[doc = "id: 254"]
30246#[doc = "Send a debug value. The index is used to discriminate between values. These values show up in the plot of QGroundControl as DEBUG N."]
30247#[derive(Debug, Clone, PartialEq)]
30248#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
30249#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
30250pub struct DEBUG_DATA {
30251 #[doc = "Timestamp (time since system boot)."]
30252 pub time_boot_ms: u32,
30253 #[doc = "DEBUG value"]
30254 pub value: f32,
30255 #[doc = "index of debug variable"]
30256 pub ind: u8,
30257}
30258impl DEBUG_DATA {
30259 pub const ENCODED_LEN: usize = 9usize;
30260 pub const DEFAULT: Self = Self {
30261 time_boot_ms: 0_u32,
30262 value: 0.0_f32,
30263 ind: 0_u8,
30264 };
30265 #[cfg(feature = "arbitrary")]
30266 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
30267 use arbitrary::{Arbitrary, Unstructured};
30268 let mut buf = [0u8; 1024];
30269 rng.fill_bytes(&mut buf);
30270 let mut unstructured = Unstructured::new(&buf);
30271 Self::arbitrary(&mut unstructured).unwrap_or_default()
30272 }
30273}
30274impl Default for DEBUG_DATA {
30275 fn default() -> Self {
30276 Self::DEFAULT.clone()
30277 }
30278}
30279impl MessageData for DEBUG_DATA {
30280 type Message = MavMessage;
30281 const ID: u32 = 254u32;
30282 const NAME: &'static str = "DEBUG";
30283 const EXTRA_CRC: u8 = 46u8;
30284 const ENCODED_LEN: usize = 9usize;
30285 fn deser(
30286 _version: MavlinkVersion,
30287 __input: &[u8],
30288 ) -> Result<Self, ::mavlink_core::error::ParserError> {
30289 let avail_len = __input.len();
30290 let mut payload_buf = [0; Self::ENCODED_LEN];
30291 let mut buf = if avail_len < Self::ENCODED_LEN {
30292 payload_buf[0..avail_len].copy_from_slice(__input);
30293 Bytes::new(&payload_buf)
30294 } else {
30295 Bytes::new(__input)
30296 };
30297 let mut __struct = Self::default();
30298 __struct.time_boot_ms = buf.get_u32_le();
30299 __struct.value = buf.get_f32_le();
30300 __struct.ind = buf.get_u8();
30301 Ok(__struct)
30302 }
30303 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
30304 let mut __tmp = BytesMut::new(bytes);
30305 #[allow(clippy::absurd_extreme_comparisons)]
30306 #[allow(unused_comparisons)]
30307 if __tmp.remaining() < Self::ENCODED_LEN {
30308 panic!(
30309 "buffer is too small (need {} bytes, but got {})",
30310 Self::ENCODED_LEN,
30311 __tmp.remaining(),
30312 )
30313 }
30314 __tmp.put_u32_le(self.time_boot_ms);
30315 __tmp.put_f32_le(self.value);
30316 __tmp.put_u8(self.ind);
30317 if matches!(version, MavlinkVersion::V2) {
30318 let len = __tmp.len();
30319 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
30320 } else {
30321 __tmp.len()
30322 }
30323 }
30324}
30325#[doc = "id: 44"]
30326#[doc = "This message is emitted as response to MISSION_REQUEST_LIST by the MAV and to initiate a write transaction. The GCS can then request the individual mission item based on the knowledge of the total number of waypoints."]
30327#[derive(Debug, Clone, PartialEq)]
30328#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
30329#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
30330pub struct MISSION_COUNT_DATA {
30331 #[doc = "Number of mission items in the sequence"]
30332 pub count: u16,
30333 #[doc = "System ID"]
30334 pub target_system: u8,
30335 #[doc = "Component ID"]
30336 pub target_component: u8,
30337 #[doc = "Mission type."]
30338 #[cfg_attr(feature = "serde", serde(default))]
30339 pub mission_type: MavMissionType,
30340 #[doc = "Id of current on-vehicle mission, fence, or rally point plan (on download from vehicle). This field is used when downloading a plan from a vehicle to a GCS. 0 on upload to the vehicle from GCS. 0 if plan ids are not supported. The current on-vehicle plan ids are streamed in `MISSION_CURRENT`, allowing a GCS to determine if any part of the plan has changed and needs to be re-uploaded. The ids are recalculated by the vehicle when any part of the on-vehicle plan changes (when a new plan is uploaded, the vehicle returns the new id to the GCS in MISSION_ACK)."]
30341 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
30342 pub opaque_id: u32,
30343}
30344impl MISSION_COUNT_DATA {
30345 pub const ENCODED_LEN: usize = 9usize;
30346 pub const DEFAULT: Self = Self {
30347 count: 0_u16,
30348 target_system: 0_u8,
30349 target_component: 0_u8,
30350 mission_type: MavMissionType::DEFAULT,
30351 opaque_id: 0_u32,
30352 };
30353 #[cfg(feature = "arbitrary")]
30354 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
30355 use arbitrary::{Arbitrary, Unstructured};
30356 let mut buf = [0u8; 1024];
30357 rng.fill_bytes(&mut buf);
30358 let mut unstructured = Unstructured::new(&buf);
30359 Self::arbitrary(&mut unstructured).unwrap_or_default()
30360 }
30361}
30362impl Default for MISSION_COUNT_DATA {
30363 fn default() -> Self {
30364 Self::DEFAULT.clone()
30365 }
30366}
30367impl MessageData for MISSION_COUNT_DATA {
30368 type Message = MavMessage;
30369 const ID: u32 = 44u32;
30370 const NAME: &'static str = "MISSION_COUNT";
30371 const EXTRA_CRC: u8 = 221u8;
30372 const ENCODED_LEN: usize = 9usize;
30373 fn deser(
30374 _version: MavlinkVersion,
30375 __input: &[u8],
30376 ) -> Result<Self, ::mavlink_core::error::ParserError> {
30377 let avail_len = __input.len();
30378 let mut payload_buf = [0; Self::ENCODED_LEN];
30379 let mut buf = if avail_len < Self::ENCODED_LEN {
30380 payload_buf[0..avail_len].copy_from_slice(__input);
30381 Bytes::new(&payload_buf)
30382 } else {
30383 Bytes::new(__input)
30384 };
30385 let mut __struct = Self::default();
30386 __struct.count = buf.get_u16_le();
30387 __struct.target_system = buf.get_u8();
30388 __struct.target_component = buf.get_u8();
30389 let tmp = buf.get_u8();
30390 __struct.mission_type =
30391 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
30392 enum_type: "MavMissionType",
30393 value: tmp as u32,
30394 })?;
30395 __struct.opaque_id = buf.get_u32_le();
30396 Ok(__struct)
30397 }
30398 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
30399 let mut __tmp = BytesMut::new(bytes);
30400 #[allow(clippy::absurd_extreme_comparisons)]
30401 #[allow(unused_comparisons)]
30402 if __tmp.remaining() < Self::ENCODED_LEN {
30403 panic!(
30404 "buffer is too small (need {} bytes, but got {})",
30405 Self::ENCODED_LEN,
30406 __tmp.remaining(),
30407 )
30408 }
30409 __tmp.put_u16_le(self.count);
30410 __tmp.put_u8(self.target_system);
30411 __tmp.put_u8(self.target_component);
30412 __tmp.put_u8(self.mission_type as u8);
30413 __tmp.put_u32_le(self.opaque_id);
30414 if matches!(version, MavlinkVersion::V2) {
30415 let len = __tmp.len();
30416 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
30417 } else {
30418 __tmp.len()
30419 }
30420 }
30421}
30422#[doc = "id: 126"]
30423#[doc = "Control a serial port. This can be used for raw access to an onboard serial peripheral such as a GPS or telemetry radio. It is designed to make it possible to update the devices firmware via MAVLink messages or change the devices settings. A message with zero bytes can be used to change just the baudrate."]
30424#[derive(Debug, Clone, PartialEq)]
30425#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
30426#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
30427pub struct SERIAL_CONTROL_DATA {
30428 #[doc = "Baudrate of transfer. Zero means no change."]
30429 pub baudrate: u32,
30430 #[doc = "Timeout for reply data"]
30431 pub timeout: u16,
30432 #[doc = "Serial control device type."]
30433 pub device: SerialControlDev,
30434 #[doc = "Bitmap of serial control flags."]
30435 pub flags: SerialControlFlag,
30436 #[doc = "how many bytes in this transfer"]
30437 pub count: u8,
30438 #[doc = "serial data"]
30439 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30440 pub data: [u8; 70],
30441 #[doc = "System ID"]
30442 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
30443 pub target_system: u8,
30444 #[doc = "Component ID"]
30445 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
30446 pub target_component: u8,
30447}
30448impl SERIAL_CONTROL_DATA {
30449 pub const ENCODED_LEN: usize = 81usize;
30450 pub const DEFAULT: Self = Self {
30451 baudrate: 0_u32,
30452 timeout: 0_u16,
30453 device: SerialControlDev::DEFAULT,
30454 flags: SerialControlFlag::DEFAULT,
30455 count: 0_u8,
30456 data: [0_u8; 70usize],
30457 target_system: 0_u8,
30458 target_component: 0_u8,
30459 };
30460 #[cfg(feature = "arbitrary")]
30461 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
30462 use arbitrary::{Arbitrary, Unstructured};
30463 let mut buf = [0u8; 1024];
30464 rng.fill_bytes(&mut buf);
30465 let mut unstructured = Unstructured::new(&buf);
30466 Self::arbitrary(&mut unstructured).unwrap_or_default()
30467 }
30468}
30469impl Default for SERIAL_CONTROL_DATA {
30470 fn default() -> Self {
30471 Self::DEFAULT.clone()
30472 }
30473}
30474impl MessageData for SERIAL_CONTROL_DATA {
30475 type Message = MavMessage;
30476 const ID: u32 = 126u32;
30477 const NAME: &'static str = "SERIAL_CONTROL";
30478 const EXTRA_CRC: u8 = 220u8;
30479 const ENCODED_LEN: usize = 81usize;
30480 fn deser(
30481 _version: MavlinkVersion,
30482 __input: &[u8],
30483 ) -> Result<Self, ::mavlink_core::error::ParserError> {
30484 let avail_len = __input.len();
30485 let mut payload_buf = [0; Self::ENCODED_LEN];
30486 let mut buf = if avail_len < Self::ENCODED_LEN {
30487 payload_buf[0..avail_len].copy_from_slice(__input);
30488 Bytes::new(&payload_buf)
30489 } else {
30490 Bytes::new(__input)
30491 };
30492 let mut __struct = Self::default();
30493 __struct.baudrate = buf.get_u32_le();
30494 __struct.timeout = buf.get_u16_le();
30495 let tmp = buf.get_u8();
30496 __struct.device =
30497 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
30498 enum_type: "SerialControlDev",
30499 value: tmp as u32,
30500 })?;
30501 let tmp = buf.get_u8();
30502 __struct.flags = SerialControlFlag::from_bits(tmp & SerialControlFlag::all().bits())
30503 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
30504 flag_type: "SerialControlFlag",
30505 value: tmp as u32,
30506 })?;
30507 __struct.count = buf.get_u8();
30508 for v in &mut __struct.data {
30509 let val = buf.get_u8();
30510 *v = val;
30511 }
30512 __struct.target_system = buf.get_u8();
30513 __struct.target_component = buf.get_u8();
30514 Ok(__struct)
30515 }
30516 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
30517 let mut __tmp = BytesMut::new(bytes);
30518 #[allow(clippy::absurd_extreme_comparisons)]
30519 #[allow(unused_comparisons)]
30520 if __tmp.remaining() < Self::ENCODED_LEN {
30521 panic!(
30522 "buffer is too small (need {} bytes, but got {})",
30523 Self::ENCODED_LEN,
30524 __tmp.remaining(),
30525 )
30526 }
30527 __tmp.put_u32_le(self.baudrate);
30528 __tmp.put_u16_le(self.timeout);
30529 __tmp.put_u8(self.device as u8);
30530 __tmp.put_u8(self.flags.bits());
30531 __tmp.put_u8(self.count);
30532 for val in &self.data {
30533 __tmp.put_u8(*val);
30534 }
30535 __tmp.put_u8(self.target_system);
30536 __tmp.put_u8(self.target_component);
30537 if matches!(version, MavlinkVersion::V2) {
30538 let len = __tmp.len();
30539 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
30540 } else {
30541 __tmp.len()
30542 }
30543 }
30544}
30545#[doc = "id: 124"]
30546#[doc = "Second GPS data."]
30547#[derive(Debug, Clone, PartialEq)]
30548#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
30549#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
30550pub struct GPS2_RAW_DATA {
30551 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
30552 pub time_usec: u64,
30553 #[doc = "Latitude (WGS84)"]
30554 pub lat: i32,
30555 #[doc = "Longitude (WGS84)"]
30556 pub lon: i32,
30557 #[doc = "Altitude (MSL). Positive for up."]
30558 pub alt: i32,
30559 #[doc = "Age of DGPS info"]
30560 pub dgps_age: u32,
30561 #[doc = "GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX"]
30562 pub eph: u16,
30563 #[doc = "GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX"]
30564 pub epv: u16,
30565 #[doc = "GPS ground speed. If unknown, set to: UINT16_MAX"]
30566 pub vel: u16,
30567 #[doc = "Course over ground (NOT heading, but direction of movement): 0.0..359.99 degrees. If unknown, set to: UINT16_MAX"]
30568 pub cog: u16,
30569 #[doc = "GPS fix type."]
30570 pub fix_type: GpsFixType,
30571 #[doc = "Number of satellites visible. If unknown, set to UINT8_MAX"]
30572 pub satellites_visible: u8,
30573 #[doc = "Number of DGPS satellites"]
30574 pub dgps_numch: u8,
30575 #[doc = "Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use UINT16_MAX if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north."]
30576 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
30577 pub yaw: u16,
30578 #[doc = "Altitude (above WGS84, EGM96 ellipsoid). Positive for up."]
30579 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
30580 pub alt_ellipsoid: i32,
30581 #[doc = "Position uncertainty."]
30582 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
30583 pub h_acc: u32,
30584 #[doc = "Altitude uncertainty."]
30585 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
30586 pub v_acc: u32,
30587 #[doc = "Speed uncertainty."]
30588 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
30589 pub vel_acc: u32,
30590 #[doc = "Heading / track uncertainty"]
30591 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
30592 pub hdg_acc: u32,
30593}
30594impl GPS2_RAW_DATA {
30595 pub const ENCODED_LEN: usize = 57usize;
30596 pub const DEFAULT: Self = Self {
30597 time_usec: 0_u64,
30598 lat: 0_i32,
30599 lon: 0_i32,
30600 alt: 0_i32,
30601 dgps_age: 0_u32,
30602 eph: 0_u16,
30603 epv: 0_u16,
30604 vel: 0_u16,
30605 cog: 0_u16,
30606 fix_type: GpsFixType::DEFAULT,
30607 satellites_visible: 0_u8,
30608 dgps_numch: 0_u8,
30609 yaw: 0_u16,
30610 alt_ellipsoid: 0_i32,
30611 h_acc: 0_u32,
30612 v_acc: 0_u32,
30613 vel_acc: 0_u32,
30614 hdg_acc: 0_u32,
30615 };
30616 #[cfg(feature = "arbitrary")]
30617 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
30618 use arbitrary::{Arbitrary, Unstructured};
30619 let mut buf = [0u8; 1024];
30620 rng.fill_bytes(&mut buf);
30621 let mut unstructured = Unstructured::new(&buf);
30622 Self::arbitrary(&mut unstructured).unwrap_or_default()
30623 }
30624}
30625impl Default for GPS2_RAW_DATA {
30626 fn default() -> Self {
30627 Self::DEFAULT.clone()
30628 }
30629}
30630impl MessageData for GPS2_RAW_DATA {
30631 type Message = MavMessage;
30632 const ID: u32 = 124u32;
30633 const NAME: &'static str = "GPS2_RAW";
30634 const EXTRA_CRC: u8 = 87u8;
30635 const ENCODED_LEN: usize = 57usize;
30636 fn deser(
30637 _version: MavlinkVersion,
30638 __input: &[u8],
30639 ) -> Result<Self, ::mavlink_core::error::ParserError> {
30640 let avail_len = __input.len();
30641 let mut payload_buf = [0; Self::ENCODED_LEN];
30642 let mut buf = if avail_len < Self::ENCODED_LEN {
30643 payload_buf[0..avail_len].copy_from_slice(__input);
30644 Bytes::new(&payload_buf)
30645 } else {
30646 Bytes::new(__input)
30647 };
30648 let mut __struct = Self::default();
30649 __struct.time_usec = buf.get_u64_le();
30650 __struct.lat = buf.get_i32_le();
30651 __struct.lon = buf.get_i32_le();
30652 __struct.alt = buf.get_i32_le();
30653 __struct.dgps_age = buf.get_u32_le();
30654 __struct.eph = buf.get_u16_le();
30655 __struct.epv = buf.get_u16_le();
30656 __struct.vel = buf.get_u16_le();
30657 __struct.cog = buf.get_u16_le();
30658 let tmp = buf.get_u8();
30659 __struct.fix_type =
30660 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
30661 enum_type: "GpsFixType",
30662 value: tmp as u32,
30663 })?;
30664 __struct.satellites_visible = buf.get_u8();
30665 __struct.dgps_numch = buf.get_u8();
30666 __struct.yaw = buf.get_u16_le();
30667 __struct.alt_ellipsoid = buf.get_i32_le();
30668 __struct.h_acc = buf.get_u32_le();
30669 __struct.v_acc = buf.get_u32_le();
30670 __struct.vel_acc = buf.get_u32_le();
30671 __struct.hdg_acc = buf.get_u32_le();
30672 Ok(__struct)
30673 }
30674 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
30675 let mut __tmp = BytesMut::new(bytes);
30676 #[allow(clippy::absurd_extreme_comparisons)]
30677 #[allow(unused_comparisons)]
30678 if __tmp.remaining() < Self::ENCODED_LEN {
30679 panic!(
30680 "buffer is too small (need {} bytes, but got {})",
30681 Self::ENCODED_LEN,
30682 __tmp.remaining(),
30683 )
30684 }
30685 __tmp.put_u64_le(self.time_usec);
30686 __tmp.put_i32_le(self.lat);
30687 __tmp.put_i32_le(self.lon);
30688 __tmp.put_i32_le(self.alt);
30689 __tmp.put_u32_le(self.dgps_age);
30690 __tmp.put_u16_le(self.eph);
30691 __tmp.put_u16_le(self.epv);
30692 __tmp.put_u16_le(self.vel);
30693 __tmp.put_u16_le(self.cog);
30694 __tmp.put_u8(self.fix_type as u8);
30695 __tmp.put_u8(self.satellites_visible);
30696 __tmp.put_u8(self.dgps_numch);
30697 __tmp.put_u16_le(self.yaw);
30698 __tmp.put_i32_le(self.alt_ellipsoid);
30699 __tmp.put_u32_le(self.h_acc);
30700 __tmp.put_u32_le(self.v_acc);
30701 __tmp.put_u32_le(self.vel_acc);
30702 __tmp.put_u32_le(self.hdg_acc);
30703 if matches!(version, MavlinkVersion::V2) {
30704 let len = __tmp.len();
30705 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
30706 } else {
30707 __tmp.len()
30708 }
30709 }
30710}
30711#[doc = "id: 264"]
30712#[doc = "Flight information. This includes time since boot for arm, takeoff, and land, and a flight number. Takeoff and landing values reset to zero on arm. This can be requested using MAV_CMD_REQUEST_MESSAGE. Note, some fields are misnamed - timestamps are from boot (not UTC) and the flight_uuid is a sequence number."]
30713#[derive(Debug, Clone, PartialEq)]
30714#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
30715#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
30716pub struct FLIGHT_INFORMATION_DATA {
30717 #[doc = "Timestamp at arming (since system boot). Set to 0 on boot. Set value on arming. Note, field is misnamed UTC."]
30718 pub arming_time_utc: u64,
30719 #[doc = "Timestamp at takeoff (since system boot). Set to 0 at boot and on arming. Note, field is misnamed UTC."]
30720 pub takeoff_time_utc: u64,
30721 #[doc = "Flight number. Note, field is misnamed UUID."]
30722 pub flight_uuid: u64,
30723 #[doc = "Timestamp (time since system boot)."]
30724 pub time_boot_ms: u32,
30725 #[doc = "Timestamp at landing (in ms since system boot). Set to 0 at boot and on arming."]
30726 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
30727 pub landing_time: u32,
30728}
30729impl FLIGHT_INFORMATION_DATA {
30730 pub const ENCODED_LEN: usize = 32usize;
30731 pub const DEFAULT: Self = Self {
30732 arming_time_utc: 0_u64,
30733 takeoff_time_utc: 0_u64,
30734 flight_uuid: 0_u64,
30735 time_boot_ms: 0_u32,
30736 landing_time: 0_u32,
30737 };
30738 #[cfg(feature = "arbitrary")]
30739 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
30740 use arbitrary::{Arbitrary, Unstructured};
30741 let mut buf = [0u8; 1024];
30742 rng.fill_bytes(&mut buf);
30743 let mut unstructured = Unstructured::new(&buf);
30744 Self::arbitrary(&mut unstructured).unwrap_or_default()
30745 }
30746}
30747impl Default for FLIGHT_INFORMATION_DATA {
30748 fn default() -> Self {
30749 Self::DEFAULT.clone()
30750 }
30751}
30752impl MessageData for FLIGHT_INFORMATION_DATA {
30753 type Message = MavMessage;
30754 const ID: u32 = 264u32;
30755 const NAME: &'static str = "FLIGHT_INFORMATION";
30756 const EXTRA_CRC: u8 = 49u8;
30757 const ENCODED_LEN: usize = 32usize;
30758 fn deser(
30759 _version: MavlinkVersion,
30760 __input: &[u8],
30761 ) -> Result<Self, ::mavlink_core::error::ParserError> {
30762 let avail_len = __input.len();
30763 let mut payload_buf = [0; Self::ENCODED_LEN];
30764 let mut buf = if avail_len < Self::ENCODED_LEN {
30765 payload_buf[0..avail_len].copy_from_slice(__input);
30766 Bytes::new(&payload_buf)
30767 } else {
30768 Bytes::new(__input)
30769 };
30770 let mut __struct = Self::default();
30771 __struct.arming_time_utc = buf.get_u64_le();
30772 __struct.takeoff_time_utc = buf.get_u64_le();
30773 __struct.flight_uuid = buf.get_u64_le();
30774 __struct.time_boot_ms = buf.get_u32_le();
30775 __struct.landing_time = buf.get_u32_le();
30776 Ok(__struct)
30777 }
30778 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
30779 let mut __tmp = BytesMut::new(bytes);
30780 #[allow(clippy::absurd_extreme_comparisons)]
30781 #[allow(unused_comparisons)]
30782 if __tmp.remaining() < Self::ENCODED_LEN {
30783 panic!(
30784 "buffer is too small (need {} bytes, but got {})",
30785 Self::ENCODED_LEN,
30786 __tmp.remaining(),
30787 )
30788 }
30789 __tmp.put_u64_le(self.arming_time_utc);
30790 __tmp.put_u64_le(self.takeoff_time_utc);
30791 __tmp.put_u64_le(self.flight_uuid);
30792 __tmp.put_u32_le(self.time_boot_ms);
30793 __tmp.put_u32_le(self.landing_time);
30794 if matches!(version, MavlinkVersion::V2) {
30795 let len = __tmp.len();
30796 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
30797 } else {
30798 __tmp.len()
30799 }
30800 }
30801}
30802#[doc = "id: 282"]
30803#[doc = "High level message to control a gimbal's attitude. This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case."]
30804#[derive(Debug, Clone, PartialEq)]
30805#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
30806#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
30807pub struct GIMBAL_MANAGER_SET_ATTITUDE_DATA {
30808 #[doc = "High level gimbal manager flags to use."]
30809 pub flags: GimbalManagerFlags,
30810 #[doc = "Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_MANAGER_FLAGS_YAW_LOCK is set)"]
30811 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30812 pub q: [f32; 4],
30813 #[doc = "X component of angular velocity, positive is rolling to the right, NaN to be ignored."]
30814 pub angular_velocity_x: f32,
30815 #[doc = "Y component of angular velocity, positive is pitching up, NaN to be ignored."]
30816 pub angular_velocity_y: f32,
30817 #[doc = "Z component of angular velocity, positive is yawing to the right, NaN to be ignored."]
30818 pub angular_velocity_z: f32,
30819 #[doc = "System ID"]
30820 pub target_system: u8,
30821 #[doc = "Component ID"]
30822 pub target_component: u8,
30823 #[doc = "Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals)."]
30824 pub gimbal_device_id: u8,
30825}
30826impl GIMBAL_MANAGER_SET_ATTITUDE_DATA {
30827 pub const ENCODED_LEN: usize = 35usize;
30828 pub const DEFAULT: Self = Self {
30829 flags: GimbalManagerFlags::DEFAULT,
30830 q: [0.0_f32; 4usize],
30831 angular_velocity_x: 0.0_f32,
30832 angular_velocity_y: 0.0_f32,
30833 angular_velocity_z: 0.0_f32,
30834 target_system: 0_u8,
30835 target_component: 0_u8,
30836 gimbal_device_id: 0_u8,
30837 };
30838 #[cfg(feature = "arbitrary")]
30839 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
30840 use arbitrary::{Arbitrary, Unstructured};
30841 let mut buf = [0u8; 1024];
30842 rng.fill_bytes(&mut buf);
30843 let mut unstructured = Unstructured::new(&buf);
30844 Self::arbitrary(&mut unstructured).unwrap_or_default()
30845 }
30846}
30847impl Default for GIMBAL_MANAGER_SET_ATTITUDE_DATA {
30848 fn default() -> Self {
30849 Self::DEFAULT.clone()
30850 }
30851}
30852impl MessageData for GIMBAL_MANAGER_SET_ATTITUDE_DATA {
30853 type Message = MavMessage;
30854 const ID: u32 = 282u32;
30855 const NAME: &'static str = "GIMBAL_MANAGER_SET_ATTITUDE";
30856 const EXTRA_CRC: u8 = 123u8;
30857 const ENCODED_LEN: usize = 35usize;
30858 fn deser(
30859 _version: MavlinkVersion,
30860 __input: &[u8],
30861 ) -> Result<Self, ::mavlink_core::error::ParserError> {
30862 let avail_len = __input.len();
30863 let mut payload_buf = [0; Self::ENCODED_LEN];
30864 let mut buf = if avail_len < Self::ENCODED_LEN {
30865 payload_buf[0..avail_len].copy_from_slice(__input);
30866 Bytes::new(&payload_buf)
30867 } else {
30868 Bytes::new(__input)
30869 };
30870 let mut __struct = Self::default();
30871 let tmp = buf.get_u32_le();
30872 __struct.flags = GimbalManagerFlags::from_bits(tmp & GimbalManagerFlags::all().bits())
30873 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
30874 flag_type: "GimbalManagerFlags",
30875 value: tmp as u32,
30876 })?;
30877 for v in &mut __struct.q {
30878 let val = buf.get_f32_le();
30879 *v = val;
30880 }
30881 __struct.angular_velocity_x = buf.get_f32_le();
30882 __struct.angular_velocity_y = buf.get_f32_le();
30883 __struct.angular_velocity_z = buf.get_f32_le();
30884 __struct.target_system = buf.get_u8();
30885 __struct.target_component = buf.get_u8();
30886 __struct.gimbal_device_id = buf.get_u8();
30887 Ok(__struct)
30888 }
30889 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
30890 let mut __tmp = BytesMut::new(bytes);
30891 #[allow(clippy::absurd_extreme_comparisons)]
30892 #[allow(unused_comparisons)]
30893 if __tmp.remaining() < Self::ENCODED_LEN {
30894 panic!(
30895 "buffer is too small (need {} bytes, but got {})",
30896 Self::ENCODED_LEN,
30897 __tmp.remaining(),
30898 )
30899 }
30900 __tmp.put_u32_le(self.flags.bits());
30901 for val in &self.q {
30902 __tmp.put_f32_le(*val);
30903 }
30904 __tmp.put_f32_le(self.angular_velocity_x);
30905 __tmp.put_f32_le(self.angular_velocity_y);
30906 __tmp.put_f32_le(self.angular_velocity_z);
30907 __tmp.put_u8(self.target_system);
30908 __tmp.put_u8(self.target_component);
30909 __tmp.put_u8(self.gimbal_device_id);
30910 if matches!(version, MavlinkVersion::V2) {
30911 let len = __tmp.len();
30912 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
30913 } else {
30914 __tmp.len()
30915 }
30916 }
30917}
30918#[derive(Clone, PartialEq, Debug)]
30919#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
30920#[cfg_attr(feature = "serde", serde(tag = "type"))]
30921#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
30922#[repr(u32)]
30923pub enum MavMessage {
30924 EVENT(EVENT_DATA),
30925 PROTOCOL_VERSION(PROTOCOL_VERSION_DATA),
30926 PARAM_VALUE(PARAM_VALUE_DATA),
30927 HIL_OPTICAL_FLOW(HIL_OPTICAL_FLOW_DATA),
30928 DISTANCE_SENSOR(DISTANCE_SENSOR_DATA),
30929 GPS_INPUT(GPS_INPUT_DATA),
30930 CAMERA_INFORMATION(CAMERA_INFORMATION_DATA),
30931 GIMBAL_DEVICE_INFORMATION(GIMBAL_DEVICE_INFORMATION_DATA),
30932 SYSTEM_TIME(SYSTEM_TIME_DATA),
30933 SET_HOME_POSITION(SET_HOME_POSITION_DATA),
30934 STATUSTEXT(STATUSTEXT_DATA),
30935 ATTITUDE(ATTITUDE_DATA),
30936 OPEN_DRONE_ID_AUTHENTICATION(OPEN_DRONE_ID_AUTHENTICATION_DATA),
30937 HIL_STATE_QUATERNION(HIL_STATE_QUATERNION_DATA),
30938 EXTENDED_SYS_STATE(EXTENDED_SYS_STATE_DATA),
30939 TRAJECTORY_REPRESENTATION_WAYPOINTS(TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA),
30940 COLLISION(COLLISION_DATA),
30941 MISSION_ACK(MISSION_ACK_DATA),
30942 SET_POSITION_TARGET_GLOBAL_INT(SET_POSITION_TARGET_GLOBAL_INT_DATA),
30943 ESC_INFO(ESC_INFO_DATA),
30944 PLAY_TUNE_V2(PLAY_TUNE_V2_DATA),
30945 SERVO_OUTPUT_RAW(SERVO_OUTPUT_RAW_DATA),
30946 VICON_POSITION_ESTIMATE(VICON_POSITION_ESTIMATE_DATA),
30947 OPEN_DRONE_ID_SELF_ID(OPEN_DRONE_ID_SELF_ID_DATA),
30948 RC_CHANNELS_SCALED(RC_CHANNELS_SCALED_DATA),
30949 VIDEO_STREAM_STATUS(VIDEO_STREAM_STATUS_DATA),
30950 VISION_SPEED_ESTIMATE(VISION_SPEED_ESTIMATE_DATA),
30951 WIND_COV(WIND_COV_DATA),
30952 SCALED_IMU(SCALED_IMU_DATA),
30953 ORBIT_EXECUTION_STATUS(ORBIT_EXECUTION_STATUS_DATA),
30954 TERRAIN_REPORT(TERRAIN_REPORT_DATA),
30955 BATTERY_STATUS(BATTERY_STATUS_DATA),
30956 ESC_STATUS(ESC_STATUS_DATA),
30957 SCALED_IMU3(SCALED_IMU3_DATA),
30958 ACTUATOR_CONTROL_TARGET(ACTUATOR_CONTROL_TARGET_DATA),
30959 GPS_RAW_INT(GPS_RAW_INT_DATA),
30960 PARAM_SET(PARAM_SET_DATA),
30961 POSITION_TARGET_LOCAL_NED(POSITION_TARGET_LOCAL_NED_DATA),
30962 CURRENT_MODE(CURRENT_MODE_DATA),
30963 AIS_VESSEL(AIS_VESSEL_DATA),
30964 ENCAPSULATED_DATA(ENCAPSULATED_DATA_DATA),
30965 ILLUMINATOR_STATUS(ILLUMINATOR_STATUS_DATA),
30966 FOLLOW_TARGET(FOLLOW_TARGET_DATA),
30967 RC_CHANNELS_RAW(RC_CHANNELS_RAW_DATA),
30968 SET_ACTUATOR_CONTROL_TARGET(SET_ACTUATOR_CONTROL_TARGET_DATA),
30969 ADSB_VEHICLE(ADSB_VEHICLE_DATA),
30970 UAVCAN_NODE_INFO(UAVCAN_NODE_INFO_DATA),
30971 UAVCAN_NODE_STATUS(UAVCAN_NODE_STATUS_DATA),
30972 GLOBAL_VISION_POSITION_ESTIMATE(GLOBAL_VISION_POSITION_ESTIMATE_DATA),
30973 V2_EXTENSION(V2_EXTENSION_DATA),
30974 GPS_RTK(GPS_RTK_DATA),
30975 WIFI_CONFIG_AP(WIFI_CONFIG_AP_DATA),
30976 COMPONENT_INFORMATION(COMPONENT_INFORMATION_DATA),
30977 LOG_REQUEST_DATA(LOG_REQUEST_DATA_DATA),
30978 HIL_RC_INPUTS_RAW(HIL_RC_INPUTS_RAW_DATA),
30979 ACTUATOR_OUTPUT_STATUS(ACTUATOR_OUTPUT_STATUS_DATA),
30980 TIMESYNC(TIMESYNC_DATA),
30981 LOGGING_DATA(LOGGING_DATA_DATA),
30982 CAN_FILTER_MODIFY(CAN_FILTER_MODIFY_DATA),
30983 HYGROMETER_SENSOR(HYGROMETER_SENSOR_DATA),
30984 BATTERY_INFO(BATTERY_INFO_DATA),
30985 PARAM_EXT_SET(PARAM_EXT_SET_DATA),
30986 SAFETY_ALLOWED_AREA(SAFETY_ALLOWED_AREA_DATA),
30987 EFI_STATUS(EFI_STATUS_DATA),
30988 AUTOPILOT_VERSION(AUTOPILOT_VERSION_DATA),
30989 SET_MODE(SET_MODE_DATA),
30990 PARAM_MAP_RC(PARAM_MAP_RC_DATA),
30991 PARAM_EXT_REQUEST_READ(PARAM_EXT_REQUEST_READ_DATA),
30992 SCALED_IMU2(SCALED_IMU2_DATA),
30993 PLAY_TUNE(PLAY_TUNE_DATA),
30994 PARAM_REQUEST_LIST(PARAM_REQUEST_LIST_DATA),
30995 AUTH_KEY(AUTH_KEY_DATA),
30996 COMMAND_CANCEL(COMMAND_CANCEL_DATA),
30997 MANUAL_CONTROL(MANUAL_CONTROL_DATA),
30998 COMMAND_INT(COMMAND_INT_DATA),
30999 HIL_CONTROLS(HIL_CONTROLS_DATA),
31000 VISION_POSITION_ESTIMATE(VISION_POSITION_ESTIMATE_DATA),
31001 GPS_RTCM_DATA(GPS_RTCM_DATA_DATA),
31002 MEMORY_VECT(MEMORY_VECT_DATA),
31003 BUTTON_CHANGE(BUTTON_CHANGE_DATA),
31004 UTM_GLOBAL_POSITION(UTM_GLOBAL_POSITION_DATA),
31005 WHEEL_DISTANCE(WHEEL_DISTANCE_DATA),
31006 HIGHRES_IMU(HIGHRES_IMU_DATA),
31007 CAMERA_TRIGGER(CAMERA_TRIGGER_DATA),
31008 GPS_INJECT_DATA(GPS_INJECT_DATA_DATA),
31009 CAMERA_THERMAL_RANGE(CAMERA_THERMAL_RANGE_DATA),
31010 RAW_RPM(RAW_RPM_DATA),
31011 REQUEST_EVENT(REQUEST_EVENT_DATA),
31012 LOCAL_POSITION_NED_COV(LOCAL_POSITION_NED_COV_DATA),
31013 GLOBAL_POSITION_INT_COV(GLOBAL_POSITION_INT_COV_DATA),
31014 LOCAL_POSITION_NED(LOCAL_POSITION_NED_DATA),
31015 REQUEST_DATA_STREAM(REQUEST_DATA_STREAM_DATA),
31016 TERRAIN_DATA(TERRAIN_DATA_DATA),
31017 CAMERA_FOV_STATUS(CAMERA_FOV_STATUS_DATA),
31018 TERRAIN_CHECK(TERRAIN_CHECK_DATA),
31019 HOME_POSITION(HOME_POSITION_DATA),
31020 HIL_SENSOR(HIL_SENSOR_DATA),
31021 POWER_STATUS(POWER_STATUS_DATA),
31022 HIL_ACTUATOR_CONTROLS(HIL_ACTUATOR_CONTROLS_DATA),
31023 GLOBAL_POSITION_INT(GLOBAL_POSITION_INT_DATA),
31024 CELLULAR_CONFIG(CELLULAR_CONFIG_DATA),
31025 AVAILABLE_MODES_MONITOR(AVAILABLE_MODES_MONITOR_DATA),
31026 GPS_STATUS(GPS_STATUS_DATA),
31027 SCALED_PRESSURE(SCALED_PRESSURE_DATA),
31028 OPTICAL_FLOW(OPTICAL_FLOW_DATA),
31029 OPEN_DRONE_ID_ARM_STATUS(OPEN_DRONE_ID_ARM_STATUS_DATA),
31030 RC_CHANNELS_OVERRIDE(RC_CHANNELS_OVERRIDE_DATA),
31031 LOG_DATA(LOG_DATA_DATA),
31032 MISSION_REQUEST_LIST(MISSION_REQUEST_LIST_DATA),
31033 ATTITUDE_QUATERNION_COV(ATTITUDE_QUATERNION_COV_DATA),
31034 POSITION_TARGET_GLOBAL_INT(POSITION_TARGET_GLOBAL_INT_DATA),
31035 GPS2_RTK(GPS2_RTK_DATA),
31036 RESOURCE_REQUEST(RESOURCE_REQUEST_DATA),
31037 ESTIMATOR_STATUS(ESTIMATOR_STATUS_DATA),
31038 ONBOARD_COMPUTER_STATUS(ONBOARD_COMPUTER_STATUS_DATA),
31039 LINK_NODE_STATUS(LINK_NODE_STATUS_DATA),
31040 CONTROL_SYSTEM_STATE(CONTROL_SYSTEM_STATE_DATA),
31041 MESSAGE_INTERVAL(MESSAGE_INTERVAL_DATA),
31042 ODOMETRY(ODOMETRY_DATA),
31043 VIDEO_STREAM_INFORMATION(VIDEO_STREAM_INFORMATION_DATA),
31044 CAMERA_TRACKING_GEO_STATUS(CAMERA_TRACKING_GEO_STATUS_DATA),
31045 COMPONENT_METADATA(COMPONENT_METADATA_DATA),
31046 RC_CHANNELS(RC_CHANNELS_DATA),
31047 ATTITUDE_TARGET(ATTITUDE_TARGET_DATA),
31048 CAMERA_TRACKING_IMAGE_STATUS(CAMERA_TRACKING_IMAGE_STATUS_DATA),
31049 MISSION_CURRENT(MISSION_CURRENT_DATA),
31050 LOG_REQUEST_LIST(LOG_REQUEST_LIST_DATA),
31051 ISBD_LINK_STATUS(ISBD_LINK_STATUS_DATA),
31052 PARAM_EXT_ACK(PARAM_EXT_ACK_DATA),
31053 SETUP_SIGNING(SETUP_SIGNING_DATA),
31054 AVAILABLE_MODES(AVAILABLE_MODES_DATA),
31055 SAFETY_SET_ALLOWED_AREA(SAFETY_SET_ALLOWED_AREA_DATA),
31056 SET_ATTITUDE_TARGET(SET_ATTITUDE_TARGET_DATA),
31057 FENCE_STATUS(FENCE_STATUS_DATA),
31058 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET(LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA),
31059 SMART_BATTERY_INFO(SMART_BATTERY_INFO_DATA),
31060 OPEN_DRONE_ID_MESSAGE_PACK(OPEN_DRONE_ID_MESSAGE_PACK_DATA),
31061 TIME_ESTIMATE_TO_TARGET(TIME_ESTIMATE_TO_TARGET_DATA),
31062 CAMERA_CAPTURE_STATUS(CAMERA_CAPTURE_STATUS_DATA),
31063 ALTITUDE(ALTITUDE_DATA),
31064 DEBUG_VECT(DEBUG_VECT_DATA),
31065 GIMBAL_MANAGER_SET_PITCHYAW(GIMBAL_MANAGER_SET_PITCHYAW_DATA),
31066 CAMERA_IMAGE_CAPTURED(CAMERA_IMAGE_CAPTURED_DATA),
31067 COMMAND_LONG(COMMAND_LONG_DATA),
31068 PARAM_EXT_REQUEST_LIST(PARAM_EXT_REQUEST_LIST_DATA),
31069 PARAM_EXT_VALUE(PARAM_EXT_VALUE_DATA),
31070 GIMBAL_MANAGER_INFORMATION(GIMBAL_MANAGER_INFORMATION_DATA),
31071 OPEN_DRONE_ID_BASIC_ID(OPEN_DRONE_ID_BASIC_ID_DATA),
31072 SCALED_PRESSURE2(SCALED_PRESSURE2_DATA),
31073 LANDING_TARGET(LANDING_TARGET_DATA),
31074 OPEN_DRONE_ID_SYSTEM_UPDATE(OPEN_DRONE_ID_SYSTEM_UPDATE_DATA),
31075 MISSION_REQUEST_PARTIAL_LIST(MISSION_REQUEST_PARTIAL_LIST_DATA),
31076 VFR_HUD(VFR_HUD_DATA),
31077 SYS_STATUS(SYS_STATUS_DATA),
31078 GPS_GLOBAL_ORIGIN(GPS_GLOBAL_ORIGIN_DATA),
31079 GIMBAL_MANAGER_STATUS(GIMBAL_MANAGER_STATUS_DATA),
31080 LOG_ERASE(LOG_ERASE_DATA),
31081 PARAM_REQUEST_READ(PARAM_REQUEST_READ_DATA),
31082 HIL_STATE(HIL_STATE_DATA),
31083 CURRENT_EVENT_SEQUENCE(CURRENT_EVENT_SEQUENCE_DATA),
31084 LOG_ENTRY(LOG_ENTRY_DATA),
31085 MISSION_ITEM_INT(MISSION_ITEM_INT_DATA),
31086 HIGH_LATENCY2(HIGH_LATENCY2_DATA),
31087 CELLULAR_STATUS(CELLULAR_STATUS_DATA),
31088 MISSION_ITEM(MISSION_ITEM_DATA),
31089 NAV_CONTROLLER_OUTPUT(NAV_CONTROLLER_OUTPUT_DATA),
31090 GIMBAL_DEVICE_ATTITUDE_STATUS(GIMBAL_DEVICE_ATTITUDE_STATUS_DATA),
31091 STORAGE_INFORMATION(STORAGE_INFORMATION_DATA),
31092 RADIO_STATUS(RADIO_STATUS_DATA),
31093 COMPONENT_INFORMATION_BASIC(COMPONENT_INFORMATION_BASIC_DATA),
31094 NAMED_VALUE_INT(NAMED_VALUE_INT_DATA),
31095 LOG_REQUEST_END(LOG_REQUEST_END_DATA),
31096 MISSION_REQUEST(MISSION_REQUEST_DATA),
31097 SET_POSITION_TARGET_LOCAL_NED(SET_POSITION_TARGET_LOCAL_NED_DATA),
31098 LOGGING_ACK(LOGGING_ACK_DATA),
31099 CAN_FRAME(CAN_FRAME_DATA),
31100 HIGH_LATENCY(HIGH_LATENCY_DATA),
31101 VIBRATION(VIBRATION_DATA),
31102 CHANGE_OPERATOR_CONTROL(CHANGE_OPERATOR_CONTROL_DATA),
31103 MANUAL_SETPOINT(MANUAL_SETPOINT_DATA),
31104 MOUNT_ORIENTATION(MOUNT_ORIENTATION_DATA),
31105 MISSION_SET_CURRENT(MISSION_SET_CURRENT_DATA),
31106 RAW_IMU(RAW_IMU_DATA),
31107 RAW_PRESSURE(RAW_PRESSURE_DATA),
31108 DATA_STREAM(DATA_STREAM_DATA),
31109 OPEN_DRONE_ID_LOCATION(OPEN_DRONE_ID_LOCATION_DATA),
31110 TUNNEL(TUNNEL_DATA),
31111 NAMED_VALUE_FLOAT(NAMED_VALUE_FLOAT_DATA),
31112 SIM_STATE(SIM_STATE_DATA),
31113 OPEN_DRONE_ID_SYSTEM(OPEN_DRONE_ID_SYSTEM_DATA),
31114 OPEN_DRONE_ID_OPERATOR_ID(OPEN_DRONE_ID_OPERATOR_ID_DATA),
31115 MISSION_WRITE_PARTIAL_LIST(MISSION_WRITE_PARTIAL_LIST_DATA),
31116 DEBUG_FLOAT_ARRAY(DEBUG_FLOAT_ARRAY_DATA),
31117 GIMBAL_MANAGER_SET_MANUAL_CONTROL(GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA),
31118 PING(PING_DATA),
31119 CAMERA_SETTINGS(CAMERA_SETTINGS_DATA),
31120 TERRAIN_REQUEST(TERRAIN_REQUEST_DATA),
31121 GIMBAL_DEVICE_SET_ATTITUDE(GIMBAL_DEVICE_SET_ATTITUDE_DATA),
31122 ATT_POS_MOCAP(ATT_POS_MOCAP_DATA),
31123 HEARTBEAT(HEARTBEAT_DATA),
31124 OBSTACLE_DISTANCE(OBSTACLE_DISTANCE_DATA),
31125 OPTICAL_FLOW_RAD(OPTICAL_FLOW_RAD_DATA),
31126 HIL_GPS(HIL_GPS_DATA),
31127 WINCH_STATUS(WINCH_STATUS_DATA),
31128 GENERATOR_STATUS(GENERATOR_STATUS_DATA),
31129 FILE_TRANSFER_PROTOCOL(FILE_TRANSFER_PROTOCOL_DATA),
31130 DATA_TRANSMISSION_HANDSHAKE(DATA_TRANSMISSION_HANDSHAKE_DATA),
31131 SUPPORTED_TUNES(SUPPORTED_TUNES_DATA),
31132 SET_GPS_GLOBAL_ORIGIN(SET_GPS_GLOBAL_ORIGIN_DATA),
31133 ATTITUDE_QUATERNION(ATTITUDE_QUATERNION_DATA),
31134 TRAJECTORY_REPRESENTATION_BEZIER(TRAJECTORY_REPRESENTATION_BEZIER_DATA),
31135 FUEL_STATUS(FUEL_STATUS_DATA),
31136 MISSION_CLEAR_ALL(MISSION_CLEAR_ALL_DATA),
31137 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA),
31138 LOGGING_DATA_ACKED(LOGGING_DATA_ACKED_DATA),
31139 RESPONSE_EVENT_ERROR(RESPONSE_EVENT_ERROR_DATA),
31140 SCALED_PRESSURE3(SCALED_PRESSURE3_DATA),
31141 CANFD_FRAME(CANFD_FRAME_DATA),
31142 MISSION_REQUEST_INT(MISSION_REQUEST_INT_DATA),
31143 MAG_CAL_REPORT(MAG_CAL_REPORT_DATA),
31144 COMMAND_ACK(COMMAND_ACK_DATA),
31145 MISSION_ITEM_REACHED(MISSION_ITEM_REACHED_DATA),
31146 CHANGE_OPERATOR_CONTROL_ACK(CHANGE_OPERATOR_CONTROL_ACK_DATA),
31147 DEBUG(DEBUG_DATA),
31148 MISSION_COUNT(MISSION_COUNT_DATA),
31149 SERIAL_CONTROL(SERIAL_CONTROL_DATA),
31150 GPS2_RAW(GPS2_RAW_DATA),
31151 FLIGHT_INFORMATION(FLIGHT_INFORMATION_DATA),
31152 GIMBAL_MANAGER_SET_ATTITUDE(GIMBAL_MANAGER_SET_ATTITUDE_DATA),
31153}
31154impl MavMessage {
31155 pub const fn all_ids() -> &'static [u32] {
31156 &[
31157 0u32, 1u32, 2u32, 4u32, 5u32, 6u32, 7u32, 8u32, 11u32, 20u32, 21u32, 22u32, 23u32,
31158 24u32, 25u32, 26u32, 27u32, 28u32, 29u32, 30u32, 31u32, 32u32, 33u32, 34u32, 35u32,
31159 36u32, 37u32, 38u32, 39u32, 40u32, 41u32, 42u32, 43u32, 44u32, 45u32, 46u32, 47u32,
31160 48u32, 49u32, 50u32, 51u32, 54u32, 55u32, 61u32, 62u32, 63u32, 64u32, 65u32, 66u32,
31161 67u32, 69u32, 70u32, 73u32, 74u32, 75u32, 76u32, 77u32, 80u32, 81u32, 82u32, 83u32,
31162 84u32, 85u32, 86u32, 87u32, 89u32, 90u32, 91u32, 92u32, 93u32, 100u32, 101u32, 102u32,
31163 103u32, 104u32, 105u32, 106u32, 107u32, 108u32, 109u32, 110u32, 111u32, 112u32, 113u32,
31164 114u32, 115u32, 116u32, 117u32, 118u32, 119u32, 120u32, 121u32, 122u32, 123u32, 124u32,
31165 125u32, 126u32, 127u32, 128u32, 129u32, 130u32, 131u32, 132u32, 133u32, 134u32, 135u32,
31166 136u32, 137u32, 138u32, 139u32, 140u32, 141u32, 142u32, 143u32, 144u32, 146u32, 147u32,
31167 148u32, 149u32, 162u32, 192u32, 225u32, 230u32, 231u32, 232u32, 233u32, 234u32, 235u32,
31168 241u32, 242u32, 243u32, 244u32, 245u32, 246u32, 247u32, 248u32, 249u32, 250u32, 251u32,
31169 252u32, 253u32, 254u32, 256u32, 257u32, 258u32, 259u32, 260u32, 261u32, 262u32, 263u32,
31170 264u32, 265u32, 266u32, 267u32, 268u32, 269u32, 270u32, 271u32, 275u32, 276u32, 277u32,
31171 280u32, 281u32, 282u32, 283u32, 284u32, 285u32, 286u32, 287u32, 288u32, 290u32, 291u32,
31172 299u32, 300u32, 301u32, 310u32, 311u32, 320u32, 321u32, 322u32, 323u32, 324u32, 330u32,
31173 331u32, 332u32, 333u32, 334u32, 335u32, 336u32, 339u32, 340u32, 350u32, 360u32, 370u32,
31174 371u32, 372u32, 373u32, 375u32, 380u32, 385u32, 386u32, 387u32, 388u32, 390u32, 395u32,
31175 396u32, 397u32, 400u32, 401u32, 410u32, 411u32, 412u32, 413u32, 435u32, 436u32, 437u32,
31176 440u32, 9000u32, 9005u32, 12900u32, 12901u32, 12902u32, 12903u32, 12904u32, 12905u32,
31177 12915u32, 12918u32, 12919u32, 12920u32,
31178 ]
31179 }
31180}
31181impl Message for MavMessage {
31182 fn parse(
31183 version: MavlinkVersion,
31184 id: u32,
31185 payload: &[u8],
31186 ) -> Result<Self, ::mavlink_core::error::ParserError> {
31187 match id {
31188 EVENT_DATA::ID => EVENT_DATA::deser(version, payload).map(Self::EVENT),
31189 PROTOCOL_VERSION_DATA::ID => {
31190 PROTOCOL_VERSION_DATA::deser(version, payload).map(Self::PROTOCOL_VERSION)
31191 }
31192 PARAM_VALUE_DATA::ID => {
31193 PARAM_VALUE_DATA::deser(version, payload).map(Self::PARAM_VALUE)
31194 }
31195 HIL_OPTICAL_FLOW_DATA::ID => {
31196 HIL_OPTICAL_FLOW_DATA::deser(version, payload).map(Self::HIL_OPTICAL_FLOW)
31197 }
31198 DISTANCE_SENSOR_DATA::ID => {
31199 DISTANCE_SENSOR_DATA::deser(version, payload).map(Self::DISTANCE_SENSOR)
31200 }
31201 GPS_INPUT_DATA::ID => GPS_INPUT_DATA::deser(version, payload).map(Self::GPS_INPUT),
31202 CAMERA_INFORMATION_DATA::ID => {
31203 CAMERA_INFORMATION_DATA::deser(version, payload).map(Self::CAMERA_INFORMATION)
31204 }
31205 GIMBAL_DEVICE_INFORMATION_DATA::ID => {
31206 GIMBAL_DEVICE_INFORMATION_DATA::deser(version, payload)
31207 .map(Self::GIMBAL_DEVICE_INFORMATION)
31208 }
31209 SYSTEM_TIME_DATA::ID => {
31210 SYSTEM_TIME_DATA::deser(version, payload).map(Self::SYSTEM_TIME)
31211 }
31212 SET_HOME_POSITION_DATA::ID => {
31213 SET_HOME_POSITION_DATA::deser(version, payload).map(Self::SET_HOME_POSITION)
31214 }
31215 STATUSTEXT_DATA::ID => STATUSTEXT_DATA::deser(version, payload).map(Self::STATUSTEXT),
31216 ATTITUDE_DATA::ID => ATTITUDE_DATA::deser(version, payload).map(Self::ATTITUDE),
31217 OPEN_DRONE_ID_AUTHENTICATION_DATA::ID => {
31218 OPEN_DRONE_ID_AUTHENTICATION_DATA::deser(version, payload)
31219 .map(Self::OPEN_DRONE_ID_AUTHENTICATION)
31220 }
31221 HIL_STATE_QUATERNION_DATA::ID => {
31222 HIL_STATE_QUATERNION_DATA::deser(version, payload).map(Self::HIL_STATE_QUATERNION)
31223 }
31224 EXTENDED_SYS_STATE_DATA::ID => {
31225 EXTENDED_SYS_STATE_DATA::deser(version, payload).map(Self::EXTENDED_SYS_STATE)
31226 }
31227 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::ID => {
31228 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::deser(version, payload)
31229 .map(Self::TRAJECTORY_REPRESENTATION_WAYPOINTS)
31230 }
31231 COLLISION_DATA::ID => COLLISION_DATA::deser(version, payload).map(Self::COLLISION),
31232 MISSION_ACK_DATA::ID => {
31233 MISSION_ACK_DATA::deser(version, payload).map(Self::MISSION_ACK)
31234 }
31235 SET_POSITION_TARGET_GLOBAL_INT_DATA::ID => {
31236 SET_POSITION_TARGET_GLOBAL_INT_DATA::deser(version, payload)
31237 .map(Self::SET_POSITION_TARGET_GLOBAL_INT)
31238 }
31239 ESC_INFO_DATA::ID => ESC_INFO_DATA::deser(version, payload).map(Self::ESC_INFO),
31240 PLAY_TUNE_V2_DATA::ID => {
31241 PLAY_TUNE_V2_DATA::deser(version, payload).map(Self::PLAY_TUNE_V2)
31242 }
31243 SERVO_OUTPUT_RAW_DATA::ID => {
31244 SERVO_OUTPUT_RAW_DATA::deser(version, payload).map(Self::SERVO_OUTPUT_RAW)
31245 }
31246 VICON_POSITION_ESTIMATE_DATA::ID => {
31247 VICON_POSITION_ESTIMATE_DATA::deser(version, payload)
31248 .map(Self::VICON_POSITION_ESTIMATE)
31249 }
31250 OPEN_DRONE_ID_SELF_ID_DATA::ID => {
31251 OPEN_DRONE_ID_SELF_ID_DATA::deser(version, payload).map(Self::OPEN_DRONE_ID_SELF_ID)
31252 }
31253 RC_CHANNELS_SCALED_DATA::ID => {
31254 RC_CHANNELS_SCALED_DATA::deser(version, payload).map(Self::RC_CHANNELS_SCALED)
31255 }
31256 VIDEO_STREAM_STATUS_DATA::ID => {
31257 VIDEO_STREAM_STATUS_DATA::deser(version, payload).map(Self::VIDEO_STREAM_STATUS)
31258 }
31259 VISION_SPEED_ESTIMATE_DATA::ID => {
31260 VISION_SPEED_ESTIMATE_DATA::deser(version, payload).map(Self::VISION_SPEED_ESTIMATE)
31261 }
31262 WIND_COV_DATA::ID => WIND_COV_DATA::deser(version, payload).map(Self::WIND_COV),
31263 SCALED_IMU_DATA::ID => SCALED_IMU_DATA::deser(version, payload).map(Self::SCALED_IMU),
31264 ORBIT_EXECUTION_STATUS_DATA::ID => ORBIT_EXECUTION_STATUS_DATA::deser(version, payload)
31265 .map(Self::ORBIT_EXECUTION_STATUS),
31266 TERRAIN_REPORT_DATA::ID => {
31267 TERRAIN_REPORT_DATA::deser(version, payload).map(Self::TERRAIN_REPORT)
31268 }
31269 BATTERY_STATUS_DATA::ID => {
31270 BATTERY_STATUS_DATA::deser(version, payload).map(Self::BATTERY_STATUS)
31271 }
31272 ESC_STATUS_DATA::ID => ESC_STATUS_DATA::deser(version, payload).map(Self::ESC_STATUS),
31273 SCALED_IMU3_DATA::ID => {
31274 SCALED_IMU3_DATA::deser(version, payload).map(Self::SCALED_IMU3)
31275 }
31276 ACTUATOR_CONTROL_TARGET_DATA::ID => {
31277 ACTUATOR_CONTROL_TARGET_DATA::deser(version, payload)
31278 .map(Self::ACTUATOR_CONTROL_TARGET)
31279 }
31280 GPS_RAW_INT_DATA::ID => {
31281 GPS_RAW_INT_DATA::deser(version, payload).map(Self::GPS_RAW_INT)
31282 }
31283 PARAM_SET_DATA::ID => PARAM_SET_DATA::deser(version, payload).map(Self::PARAM_SET),
31284 POSITION_TARGET_LOCAL_NED_DATA::ID => {
31285 POSITION_TARGET_LOCAL_NED_DATA::deser(version, payload)
31286 .map(Self::POSITION_TARGET_LOCAL_NED)
31287 }
31288 CURRENT_MODE_DATA::ID => {
31289 CURRENT_MODE_DATA::deser(version, payload).map(Self::CURRENT_MODE)
31290 }
31291 AIS_VESSEL_DATA::ID => AIS_VESSEL_DATA::deser(version, payload).map(Self::AIS_VESSEL),
31292 ENCAPSULATED_DATA_DATA::ID => {
31293 ENCAPSULATED_DATA_DATA::deser(version, payload).map(Self::ENCAPSULATED_DATA)
31294 }
31295 ILLUMINATOR_STATUS_DATA::ID => {
31296 ILLUMINATOR_STATUS_DATA::deser(version, payload).map(Self::ILLUMINATOR_STATUS)
31297 }
31298 FOLLOW_TARGET_DATA::ID => {
31299 FOLLOW_TARGET_DATA::deser(version, payload).map(Self::FOLLOW_TARGET)
31300 }
31301 RC_CHANNELS_RAW_DATA::ID => {
31302 RC_CHANNELS_RAW_DATA::deser(version, payload).map(Self::RC_CHANNELS_RAW)
31303 }
31304 SET_ACTUATOR_CONTROL_TARGET_DATA::ID => {
31305 SET_ACTUATOR_CONTROL_TARGET_DATA::deser(version, payload)
31306 .map(Self::SET_ACTUATOR_CONTROL_TARGET)
31307 }
31308 ADSB_VEHICLE_DATA::ID => {
31309 ADSB_VEHICLE_DATA::deser(version, payload).map(Self::ADSB_VEHICLE)
31310 }
31311 UAVCAN_NODE_INFO_DATA::ID => {
31312 UAVCAN_NODE_INFO_DATA::deser(version, payload).map(Self::UAVCAN_NODE_INFO)
31313 }
31314 UAVCAN_NODE_STATUS_DATA::ID => {
31315 UAVCAN_NODE_STATUS_DATA::deser(version, payload).map(Self::UAVCAN_NODE_STATUS)
31316 }
31317 GLOBAL_VISION_POSITION_ESTIMATE_DATA::ID => {
31318 GLOBAL_VISION_POSITION_ESTIMATE_DATA::deser(version, payload)
31319 .map(Self::GLOBAL_VISION_POSITION_ESTIMATE)
31320 }
31321 V2_EXTENSION_DATA::ID => {
31322 V2_EXTENSION_DATA::deser(version, payload).map(Self::V2_EXTENSION)
31323 }
31324 GPS_RTK_DATA::ID => GPS_RTK_DATA::deser(version, payload).map(Self::GPS_RTK),
31325 WIFI_CONFIG_AP_DATA::ID => {
31326 WIFI_CONFIG_AP_DATA::deser(version, payload).map(Self::WIFI_CONFIG_AP)
31327 }
31328 COMPONENT_INFORMATION_DATA::ID => {
31329 COMPONENT_INFORMATION_DATA::deser(version, payload).map(Self::COMPONENT_INFORMATION)
31330 }
31331 LOG_REQUEST_DATA_DATA::ID => {
31332 LOG_REQUEST_DATA_DATA::deser(version, payload).map(Self::LOG_REQUEST_DATA)
31333 }
31334 HIL_RC_INPUTS_RAW_DATA::ID => {
31335 HIL_RC_INPUTS_RAW_DATA::deser(version, payload).map(Self::HIL_RC_INPUTS_RAW)
31336 }
31337 ACTUATOR_OUTPUT_STATUS_DATA::ID => ACTUATOR_OUTPUT_STATUS_DATA::deser(version, payload)
31338 .map(Self::ACTUATOR_OUTPUT_STATUS),
31339 TIMESYNC_DATA::ID => TIMESYNC_DATA::deser(version, payload).map(Self::TIMESYNC),
31340 LOGGING_DATA_DATA::ID => {
31341 LOGGING_DATA_DATA::deser(version, payload).map(Self::LOGGING_DATA)
31342 }
31343 CAN_FILTER_MODIFY_DATA::ID => {
31344 CAN_FILTER_MODIFY_DATA::deser(version, payload).map(Self::CAN_FILTER_MODIFY)
31345 }
31346 HYGROMETER_SENSOR_DATA::ID => {
31347 HYGROMETER_SENSOR_DATA::deser(version, payload).map(Self::HYGROMETER_SENSOR)
31348 }
31349 BATTERY_INFO_DATA::ID => {
31350 BATTERY_INFO_DATA::deser(version, payload).map(Self::BATTERY_INFO)
31351 }
31352 PARAM_EXT_SET_DATA::ID => {
31353 PARAM_EXT_SET_DATA::deser(version, payload).map(Self::PARAM_EXT_SET)
31354 }
31355 SAFETY_ALLOWED_AREA_DATA::ID => {
31356 SAFETY_ALLOWED_AREA_DATA::deser(version, payload).map(Self::SAFETY_ALLOWED_AREA)
31357 }
31358 EFI_STATUS_DATA::ID => EFI_STATUS_DATA::deser(version, payload).map(Self::EFI_STATUS),
31359 AUTOPILOT_VERSION_DATA::ID => {
31360 AUTOPILOT_VERSION_DATA::deser(version, payload).map(Self::AUTOPILOT_VERSION)
31361 }
31362 SET_MODE_DATA::ID => SET_MODE_DATA::deser(version, payload).map(Self::SET_MODE),
31363 PARAM_MAP_RC_DATA::ID => {
31364 PARAM_MAP_RC_DATA::deser(version, payload).map(Self::PARAM_MAP_RC)
31365 }
31366 PARAM_EXT_REQUEST_READ_DATA::ID => PARAM_EXT_REQUEST_READ_DATA::deser(version, payload)
31367 .map(Self::PARAM_EXT_REQUEST_READ),
31368 SCALED_IMU2_DATA::ID => {
31369 SCALED_IMU2_DATA::deser(version, payload).map(Self::SCALED_IMU2)
31370 }
31371 PLAY_TUNE_DATA::ID => PLAY_TUNE_DATA::deser(version, payload).map(Self::PLAY_TUNE),
31372 PARAM_REQUEST_LIST_DATA::ID => {
31373 PARAM_REQUEST_LIST_DATA::deser(version, payload).map(Self::PARAM_REQUEST_LIST)
31374 }
31375 AUTH_KEY_DATA::ID => AUTH_KEY_DATA::deser(version, payload).map(Self::AUTH_KEY),
31376 COMMAND_CANCEL_DATA::ID => {
31377 COMMAND_CANCEL_DATA::deser(version, payload).map(Self::COMMAND_CANCEL)
31378 }
31379 MANUAL_CONTROL_DATA::ID => {
31380 MANUAL_CONTROL_DATA::deser(version, payload).map(Self::MANUAL_CONTROL)
31381 }
31382 COMMAND_INT_DATA::ID => {
31383 COMMAND_INT_DATA::deser(version, payload).map(Self::COMMAND_INT)
31384 }
31385 HIL_CONTROLS_DATA::ID => {
31386 HIL_CONTROLS_DATA::deser(version, payload).map(Self::HIL_CONTROLS)
31387 }
31388 VISION_POSITION_ESTIMATE_DATA::ID => {
31389 VISION_POSITION_ESTIMATE_DATA::deser(version, payload)
31390 .map(Self::VISION_POSITION_ESTIMATE)
31391 }
31392 GPS_RTCM_DATA_DATA::ID => {
31393 GPS_RTCM_DATA_DATA::deser(version, payload).map(Self::GPS_RTCM_DATA)
31394 }
31395 MEMORY_VECT_DATA::ID => {
31396 MEMORY_VECT_DATA::deser(version, payload).map(Self::MEMORY_VECT)
31397 }
31398 BUTTON_CHANGE_DATA::ID => {
31399 BUTTON_CHANGE_DATA::deser(version, payload).map(Self::BUTTON_CHANGE)
31400 }
31401 UTM_GLOBAL_POSITION_DATA::ID => {
31402 UTM_GLOBAL_POSITION_DATA::deser(version, payload).map(Self::UTM_GLOBAL_POSITION)
31403 }
31404 WHEEL_DISTANCE_DATA::ID => {
31405 WHEEL_DISTANCE_DATA::deser(version, payload).map(Self::WHEEL_DISTANCE)
31406 }
31407 HIGHRES_IMU_DATA::ID => {
31408 HIGHRES_IMU_DATA::deser(version, payload).map(Self::HIGHRES_IMU)
31409 }
31410 CAMERA_TRIGGER_DATA::ID => {
31411 CAMERA_TRIGGER_DATA::deser(version, payload).map(Self::CAMERA_TRIGGER)
31412 }
31413 GPS_INJECT_DATA_DATA::ID => {
31414 GPS_INJECT_DATA_DATA::deser(version, payload).map(Self::GPS_INJECT_DATA)
31415 }
31416 CAMERA_THERMAL_RANGE_DATA::ID => {
31417 CAMERA_THERMAL_RANGE_DATA::deser(version, payload).map(Self::CAMERA_THERMAL_RANGE)
31418 }
31419 RAW_RPM_DATA::ID => RAW_RPM_DATA::deser(version, payload).map(Self::RAW_RPM),
31420 REQUEST_EVENT_DATA::ID => {
31421 REQUEST_EVENT_DATA::deser(version, payload).map(Self::REQUEST_EVENT)
31422 }
31423 LOCAL_POSITION_NED_COV_DATA::ID => LOCAL_POSITION_NED_COV_DATA::deser(version, payload)
31424 .map(Self::LOCAL_POSITION_NED_COV),
31425 GLOBAL_POSITION_INT_COV_DATA::ID => {
31426 GLOBAL_POSITION_INT_COV_DATA::deser(version, payload)
31427 .map(Self::GLOBAL_POSITION_INT_COV)
31428 }
31429 LOCAL_POSITION_NED_DATA::ID => {
31430 LOCAL_POSITION_NED_DATA::deser(version, payload).map(Self::LOCAL_POSITION_NED)
31431 }
31432 REQUEST_DATA_STREAM_DATA::ID => {
31433 REQUEST_DATA_STREAM_DATA::deser(version, payload).map(Self::REQUEST_DATA_STREAM)
31434 }
31435 TERRAIN_DATA_DATA::ID => {
31436 TERRAIN_DATA_DATA::deser(version, payload).map(Self::TERRAIN_DATA)
31437 }
31438 CAMERA_FOV_STATUS_DATA::ID => {
31439 CAMERA_FOV_STATUS_DATA::deser(version, payload).map(Self::CAMERA_FOV_STATUS)
31440 }
31441 TERRAIN_CHECK_DATA::ID => {
31442 TERRAIN_CHECK_DATA::deser(version, payload).map(Self::TERRAIN_CHECK)
31443 }
31444 HOME_POSITION_DATA::ID => {
31445 HOME_POSITION_DATA::deser(version, payload).map(Self::HOME_POSITION)
31446 }
31447 HIL_SENSOR_DATA::ID => HIL_SENSOR_DATA::deser(version, payload).map(Self::HIL_SENSOR),
31448 POWER_STATUS_DATA::ID => {
31449 POWER_STATUS_DATA::deser(version, payload).map(Self::POWER_STATUS)
31450 }
31451 HIL_ACTUATOR_CONTROLS_DATA::ID => {
31452 HIL_ACTUATOR_CONTROLS_DATA::deser(version, payload).map(Self::HIL_ACTUATOR_CONTROLS)
31453 }
31454 GLOBAL_POSITION_INT_DATA::ID => {
31455 GLOBAL_POSITION_INT_DATA::deser(version, payload).map(Self::GLOBAL_POSITION_INT)
31456 }
31457 CELLULAR_CONFIG_DATA::ID => {
31458 CELLULAR_CONFIG_DATA::deser(version, payload).map(Self::CELLULAR_CONFIG)
31459 }
31460 AVAILABLE_MODES_MONITOR_DATA::ID => {
31461 AVAILABLE_MODES_MONITOR_DATA::deser(version, payload)
31462 .map(Self::AVAILABLE_MODES_MONITOR)
31463 }
31464 GPS_STATUS_DATA::ID => GPS_STATUS_DATA::deser(version, payload).map(Self::GPS_STATUS),
31465 SCALED_PRESSURE_DATA::ID => {
31466 SCALED_PRESSURE_DATA::deser(version, payload).map(Self::SCALED_PRESSURE)
31467 }
31468 OPTICAL_FLOW_DATA::ID => {
31469 OPTICAL_FLOW_DATA::deser(version, payload).map(Self::OPTICAL_FLOW)
31470 }
31471 OPEN_DRONE_ID_ARM_STATUS_DATA::ID => {
31472 OPEN_DRONE_ID_ARM_STATUS_DATA::deser(version, payload)
31473 .map(Self::OPEN_DRONE_ID_ARM_STATUS)
31474 }
31475 RC_CHANNELS_OVERRIDE_DATA::ID => {
31476 RC_CHANNELS_OVERRIDE_DATA::deser(version, payload).map(Self::RC_CHANNELS_OVERRIDE)
31477 }
31478 LOG_DATA_DATA::ID => LOG_DATA_DATA::deser(version, payload).map(Self::LOG_DATA),
31479 MISSION_REQUEST_LIST_DATA::ID => {
31480 MISSION_REQUEST_LIST_DATA::deser(version, payload).map(Self::MISSION_REQUEST_LIST)
31481 }
31482 ATTITUDE_QUATERNION_COV_DATA::ID => {
31483 ATTITUDE_QUATERNION_COV_DATA::deser(version, payload)
31484 .map(Self::ATTITUDE_QUATERNION_COV)
31485 }
31486 POSITION_TARGET_GLOBAL_INT_DATA::ID => {
31487 POSITION_TARGET_GLOBAL_INT_DATA::deser(version, payload)
31488 .map(Self::POSITION_TARGET_GLOBAL_INT)
31489 }
31490 GPS2_RTK_DATA::ID => GPS2_RTK_DATA::deser(version, payload).map(Self::GPS2_RTK),
31491 RESOURCE_REQUEST_DATA::ID => {
31492 RESOURCE_REQUEST_DATA::deser(version, payload).map(Self::RESOURCE_REQUEST)
31493 }
31494 ESTIMATOR_STATUS_DATA::ID => {
31495 ESTIMATOR_STATUS_DATA::deser(version, payload).map(Self::ESTIMATOR_STATUS)
31496 }
31497 ONBOARD_COMPUTER_STATUS_DATA::ID => {
31498 ONBOARD_COMPUTER_STATUS_DATA::deser(version, payload)
31499 .map(Self::ONBOARD_COMPUTER_STATUS)
31500 }
31501 LINK_NODE_STATUS_DATA::ID => {
31502 LINK_NODE_STATUS_DATA::deser(version, payload).map(Self::LINK_NODE_STATUS)
31503 }
31504 CONTROL_SYSTEM_STATE_DATA::ID => {
31505 CONTROL_SYSTEM_STATE_DATA::deser(version, payload).map(Self::CONTROL_SYSTEM_STATE)
31506 }
31507 MESSAGE_INTERVAL_DATA::ID => {
31508 MESSAGE_INTERVAL_DATA::deser(version, payload).map(Self::MESSAGE_INTERVAL)
31509 }
31510 ODOMETRY_DATA::ID => ODOMETRY_DATA::deser(version, payload).map(Self::ODOMETRY),
31511 VIDEO_STREAM_INFORMATION_DATA::ID => {
31512 VIDEO_STREAM_INFORMATION_DATA::deser(version, payload)
31513 .map(Self::VIDEO_STREAM_INFORMATION)
31514 }
31515 CAMERA_TRACKING_GEO_STATUS_DATA::ID => {
31516 CAMERA_TRACKING_GEO_STATUS_DATA::deser(version, payload)
31517 .map(Self::CAMERA_TRACKING_GEO_STATUS)
31518 }
31519 COMPONENT_METADATA_DATA::ID => {
31520 COMPONENT_METADATA_DATA::deser(version, payload).map(Self::COMPONENT_METADATA)
31521 }
31522 RC_CHANNELS_DATA::ID => {
31523 RC_CHANNELS_DATA::deser(version, payload).map(Self::RC_CHANNELS)
31524 }
31525 ATTITUDE_TARGET_DATA::ID => {
31526 ATTITUDE_TARGET_DATA::deser(version, payload).map(Self::ATTITUDE_TARGET)
31527 }
31528 CAMERA_TRACKING_IMAGE_STATUS_DATA::ID => {
31529 CAMERA_TRACKING_IMAGE_STATUS_DATA::deser(version, payload)
31530 .map(Self::CAMERA_TRACKING_IMAGE_STATUS)
31531 }
31532 MISSION_CURRENT_DATA::ID => {
31533 MISSION_CURRENT_DATA::deser(version, payload).map(Self::MISSION_CURRENT)
31534 }
31535 LOG_REQUEST_LIST_DATA::ID => {
31536 LOG_REQUEST_LIST_DATA::deser(version, payload).map(Self::LOG_REQUEST_LIST)
31537 }
31538 ISBD_LINK_STATUS_DATA::ID => {
31539 ISBD_LINK_STATUS_DATA::deser(version, payload).map(Self::ISBD_LINK_STATUS)
31540 }
31541 PARAM_EXT_ACK_DATA::ID => {
31542 PARAM_EXT_ACK_DATA::deser(version, payload).map(Self::PARAM_EXT_ACK)
31543 }
31544 SETUP_SIGNING_DATA::ID => {
31545 SETUP_SIGNING_DATA::deser(version, payload).map(Self::SETUP_SIGNING)
31546 }
31547 AVAILABLE_MODES_DATA::ID => {
31548 AVAILABLE_MODES_DATA::deser(version, payload).map(Self::AVAILABLE_MODES)
31549 }
31550 SAFETY_SET_ALLOWED_AREA_DATA::ID => {
31551 SAFETY_SET_ALLOWED_AREA_DATA::deser(version, payload)
31552 .map(Self::SAFETY_SET_ALLOWED_AREA)
31553 }
31554 SET_ATTITUDE_TARGET_DATA::ID => {
31555 SET_ATTITUDE_TARGET_DATA::deser(version, payload).map(Self::SET_ATTITUDE_TARGET)
31556 }
31557 FENCE_STATUS_DATA::ID => {
31558 FENCE_STATUS_DATA::deser(version, payload).map(Self::FENCE_STATUS)
31559 }
31560 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::ID => {
31561 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::deser(version, payload)
31562 .map(Self::LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET)
31563 }
31564 SMART_BATTERY_INFO_DATA::ID => {
31565 SMART_BATTERY_INFO_DATA::deser(version, payload).map(Self::SMART_BATTERY_INFO)
31566 }
31567 OPEN_DRONE_ID_MESSAGE_PACK_DATA::ID => {
31568 OPEN_DRONE_ID_MESSAGE_PACK_DATA::deser(version, payload)
31569 .map(Self::OPEN_DRONE_ID_MESSAGE_PACK)
31570 }
31571 TIME_ESTIMATE_TO_TARGET_DATA::ID => {
31572 TIME_ESTIMATE_TO_TARGET_DATA::deser(version, payload)
31573 .map(Self::TIME_ESTIMATE_TO_TARGET)
31574 }
31575 CAMERA_CAPTURE_STATUS_DATA::ID => {
31576 CAMERA_CAPTURE_STATUS_DATA::deser(version, payload).map(Self::CAMERA_CAPTURE_STATUS)
31577 }
31578 ALTITUDE_DATA::ID => ALTITUDE_DATA::deser(version, payload).map(Self::ALTITUDE),
31579 DEBUG_VECT_DATA::ID => DEBUG_VECT_DATA::deser(version, payload).map(Self::DEBUG_VECT),
31580 GIMBAL_MANAGER_SET_PITCHYAW_DATA::ID => {
31581 GIMBAL_MANAGER_SET_PITCHYAW_DATA::deser(version, payload)
31582 .map(Self::GIMBAL_MANAGER_SET_PITCHYAW)
31583 }
31584 CAMERA_IMAGE_CAPTURED_DATA::ID => {
31585 CAMERA_IMAGE_CAPTURED_DATA::deser(version, payload).map(Self::CAMERA_IMAGE_CAPTURED)
31586 }
31587 COMMAND_LONG_DATA::ID => {
31588 COMMAND_LONG_DATA::deser(version, payload).map(Self::COMMAND_LONG)
31589 }
31590 PARAM_EXT_REQUEST_LIST_DATA::ID => PARAM_EXT_REQUEST_LIST_DATA::deser(version, payload)
31591 .map(Self::PARAM_EXT_REQUEST_LIST),
31592 PARAM_EXT_VALUE_DATA::ID => {
31593 PARAM_EXT_VALUE_DATA::deser(version, payload).map(Self::PARAM_EXT_VALUE)
31594 }
31595 GIMBAL_MANAGER_INFORMATION_DATA::ID => {
31596 GIMBAL_MANAGER_INFORMATION_DATA::deser(version, payload)
31597 .map(Self::GIMBAL_MANAGER_INFORMATION)
31598 }
31599 OPEN_DRONE_ID_BASIC_ID_DATA::ID => OPEN_DRONE_ID_BASIC_ID_DATA::deser(version, payload)
31600 .map(Self::OPEN_DRONE_ID_BASIC_ID),
31601 SCALED_PRESSURE2_DATA::ID => {
31602 SCALED_PRESSURE2_DATA::deser(version, payload).map(Self::SCALED_PRESSURE2)
31603 }
31604 LANDING_TARGET_DATA::ID => {
31605 LANDING_TARGET_DATA::deser(version, payload).map(Self::LANDING_TARGET)
31606 }
31607 OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::ID => {
31608 OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::deser(version, payload)
31609 .map(Self::OPEN_DRONE_ID_SYSTEM_UPDATE)
31610 }
31611 MISSION_REQUEST_PARTIAL_LIST_DATA::ID => {
31612 MISSION_REQUEST_PARTIAL_LIST_DATA::deser(version, payload)
31613 .map(Self::MISSION_REQUEST_PARTIAL_LIST)
31614 }
31615 VFR_HUD_DATA::ID => VFR_HUD_DATA::deser(version, payload).map(Self::VFR_HUD),
31616 SYS_STATUS_DATA::ID => SYS_STATUS_DATA::deser(version, payload).map(Self::SYS_STATUS),
31617 GPS_GLOBAL_ORIGIN_DATA::ID => {
31618 GPS_GLOBAL_ORIGIN_DATA::deser(version, payload).map(Self::GPS_GLOBAL_ORIGIN)
31619 }
31620 GIMBAL_MANAGER_STATUS_DATA::ID => {
31621 GIMBAL_MANAGER_STATUS_DATA::deser(version, payload).map(Self::GIMBAL_MANAGER_STATUS)
31622 }
31623 LOG_ERASE_DATA::ID => LOG_ERASE_DATA::deser(version, payload).map(Self::LOG_ERASE),
31624 PARAM_REQUEST_READ_DATA::ID => {
31625 PARAM_REQUEST_READ_DATA::deser(version, payload).map(Self::PARAM_REQUEST_READ)
31626 }
31627 HIL_STATE_DATA::ID => HIL_STATE_DATA::deser(version, payload).map(Self::HIL_STATE),
31628 CURRENT_EVENT_SEQUENCE_DATA::ID => CURRENT_EVENT_SEQUENCE_DATA::deser(version, payload)
31629 .map(Self::CURRENT_EVENT_SEQUENCE),
31630 LOG_ENTRY_DATA::ID => LOG_ENTRY_DATA::deser(version, payload).map(Self::LOG_ENTRY),
31631 MISSION_ITEM_INT_DATA::ID => {
31632 MISSION_ITEM_INT_DATA::deser(version, payload).map(Self::MISSION_ITEM_INT)
31633 }
31634 HIGH_LATENCY2_DATA::ID => {
31635 HIGH_LATENCY2_DATA::deser(version, payload).map(Self::HIGH_LATENCY2)
31636 }
31637 CELLULAR_STATUS_DATA::ID => {
31638 CELLULAR_STATUS_DATA::deser(version, payload).map(Self::CELLULAR_STATUS)
31639 }
31640 MISSION_ITEM_DATA::ID => {
31641 MISSION_ITEM_DATA::deser(version, payload).map(Self::MISSION_ITEM)
31642 }
31643 NAV_CONTROLLER_OUTPUT_DATA::ID => {
31644 NAV_CONTROLLER_OUTPUT_DATA::deser(version, payload).map(Self::NAV_CONTROLLER_OUTPUT)
31645 }
31646 GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::ID => {
31647 GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::deser(version, payload)
31648 .map(Self::GIMBAL_DEVICE_ATTITUDE_STATUS)
31649 }
31650 STORAGE_INFORMATION_DATA::ID => {
31651 STORAGE_INFORMATION_DATA::deser(version, payload).map(Self::STORAGE_INFORMATION)
31652 }
31653 RADIO_STATUS_DATA::ID => {
31654 RADIO_STATUS_DATA::deser(version, payload).map(Self::RADIO_STATUS)
31655 }
31656 COMPONENT_INFORMATION_BASIC_DATA::ID => {
31657 COMPONENT_INFORMATION_BASIC_DATA::deser(version, payload)
31658 .map(Self::COMPONENT_INFORMATION_BASIC)
31659 }
31660 NAMED_VALUE_INT_DATA::ID => {
31661 NAMED_VALUE_INT_DATA::deser(version, payload).map(Self::NAMED_VALUE_INT)
31662 }
31663 LOG_REQUEST_END_DATA::ID => {
31664 LOG_REQUEST_END_DATA::deser(version, payload).map(Self::LOG_REQUEST_END)
31665 }
31666 MISSION_REQUEST_DATA::ID => {
31667 MISSION_REQUEST_DATA::deser(version, payload).map(Self::MISSION_REQUEST)
31668 }
31669 SET_POSITION_TARGET_LOCAL_NED_DATA::ID => {
31670 SET_POSITION_TARGET_LOCAL_NED_DATA::deser(version, payload)
31671 .map(Self::SET_POSITION_TARGET_LOCAL_NED)
31672 }
31673 LOGGING_ACK_DATA::ID => {
31674 LOGGING_ACK_DATA::deser(version, payload).map(Self::LOGGING_ACK)
31675 }
31676 CAN_FRAME_DATA::ID => CAN_FRAME_DATA::deser(version, payload).map(Self::CAN_FRAME),
31677 HIGH_LATENCY_DATA::ID => {
31678 HIGH_LATENCY_DATA::deser(version, payload).map(Self::HIGH_LATENCY)
31679 }
31680 VIBRATION_DATA::ID => VIBRATION_DATA::deser(version, payload).map(Self::VIBRATION),
31681 CHANGE_OPERATOR_CONTROL_DATA::ID => {
31682 CHANGE_OPERATOR_CONTROL_DATA::deser(version, payload)
31683 .map(Self::CHANGE_OPERATOR_CONTROL)
31684 }
31685 MANUAL_SETPOINT_DATA::ID => {
31686 MANUAL_SETPOINT_DATA::deser(version, payload).map(Self::MANUAL_SETPOINT)
31687 }
31688 MOUNT_ORIENTATION_DATA::ID => {
31689 MOUNT_ORIENTATION_DATA::deser(version, payload).map(Self::MOUNT_ORIENTATION)
31690 }
31691 MISSION_SET_CURRENT_DATA::ID => {
31692 MISSION_SET_CURRENT_DATA::deser(version, payload).map(Self::MISSION_SET_CURRENT)
31693 }
31694 RAW_IMU_DATA::ID => RAW_IMU_DATA::deser(version, payload).map(Self::RAW_IMU),
31695 RAW_PRESSURE_DATA::ID => {
31696 RAW_PRESSURE_DATA::deser(version, payload).map(Self::RAW_PRESSURE)
31697 }
31698 DATA_STREAM_DATA::ID => {
31699 DATA_STREAM_DATA::deser(version, payload).map(Self::DATA_STREAM)
31700 }
31701 OPEN_DRONE_ID_LOCATION_DATA::ID => OPEN_DRONE_ID_LOCATION_DATA::deser(version, payload)
31702 .map(Self::OPEN_DRONE_ID_LOCATION),
31703 TUNNEL_DATA::ID => TUNNEL_DATA::deser(version, payload).map(Self::TUNNEL),
31704 NAMED_VALUE_FLOAT_DATA::ID => {
31705 NAMED_VALUE_FLOAT_DATA::deser(version, payload).map(Self::NAMED_VALUE_FLOAT)
31706 }
31707 SIM_STATE_DATA::ID => SIM_STATE_DATA::deser(version, payload).map(Self::SIM_STATE),
31708 OPEN_DRONE_ID_SYSTEM_DATA::ID => {
31709 OPEN_DRONE_ID_SYSTEM_DATA::deser(version, payload).map(Self::OPEN_DRONE_ID_SYSTEM)
31710 }
31711 OPEN_DRONE_ID_OPERATOR_ID_DATA::ID => {
31712 OPEN_DRONE_ID_OPERATOR_ID_DATA::deser(version, payload)
31713 .map(Self::OPEN_DRONE_ID_OPERATOR_ID)
31714 }
31715 MISSION_WRITE_PARTIAL_LIST_DATA::ID => {
31716 MISSION_WRITE_PARTIAL_LIST_DATA::deser(version, payload)
31717 .map(Self::MISSION_WRITE_PARTIAL_LIST)
31718 }
31719 DEBUG_FLOAT_ARRAY_DATA::ID => {
31720 DEBUG_FLOAT_ARRAY_DATA::deser(version, payload).map(Self::DEBUG_FLOAT_ARRAY)
31721 }
31722 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::ID => {
31723 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::deser(version, payload)
31724 .map(Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL)
31725 }
31726 PING_DATA::ID => PING_DATA::deser(version, payload).map(Self::PING),
31727 CAMERA_SETTINGS_DATA::ID => {
31728 CAMERA_SETTINGS_DATA::deser(version, payload).map(Self::CAMERA_SETTINGS)
31729 }
31730 TERRAIN_REQUEST_DATA::ID => {
31731 TERRAIN_REQUEST_DATA::deser(version, payload).map(Self::TERRAIN_REQUEST)
31732 }
31733 GIMBAL_DEVICE_SET_ATTITUDE_DATA::ID => {
31734 GIMBAL_DEVICE_SET_ATTITUDE_DATA::deser(version, payload)
31735 .map(Self::GIMBAL_DEVICE_SET_ATTITUDE)
31736 }
31737 ATT_POS_MOCAP_DATA::ID => {
31738 ATT_POS_MOCAP_DATA::deser(version, payload).map(Self::ATT_POS_MOCAP)
31739 }
31740 HEARTBEAT_DATA::ID => HEARTBEAT_DATA::deser(version, payload).map(Self::HEARTBEAT),
31741 OBSTACLE_DISTANCE_DATA::ID => {
31742 OBSTACLE_DISTANCE_DATA::deser(version, payload).map(Self::OBSTACLE_DISTANCE)
31743 }
31744 OPTICAL_FLOW_RAD_DATA::ID => {
31745 OPTICAL_FLOW_RAD_DATA::deser(version, payload).map(Self::OPTICAL_FLOW_RAD)
31746 }
31747 HIL_GPS_DATA::ID => HIL_GPS_DATA::deser(version, payload).map(Self::HIL_GPS),
31748 WINCH_STATUS_DATA::ID => {
31749 WINCH_STATUS_DATA::deser(version, payload).map(Self::WINCH_STATUS)
31750 }
31751 GENERATOR_STATUS_DATA::ID => {
31752 GENERATOR_STATUS_DATA::deser(version, payload).map(Self::GENERATOR_STATUS)
31753 }
31754 FILE_TRANSFER_PROTOCOL_DATA::ID => FILE_TRANSFER_PROTOCOL_DATA::deser(version, payload)
31755 .map(Self::FILE_TRANSFER_PROTOCOL),
31756 DATA_TRANSMISSION_HANDSHAKE_DATA::ID => {
31757 DATA_TRANSMISSION_HANDSHAKE_DATA::deser(version, payload)
31758 .map(Self::DATA_TRANSMISSION_HANDSHAKE)
31759 }
31760 SUPPORTED_TUNES_DATA::ID => {
31761 SUPPORTED_TUNES_DATA::deser(version, payload).map(Self::SUPPORTED_TUNES)
31762 }
31763 SET_GPS_GLOBAL_ORIGIN_DATA::ID => {
31764 SET_GPS_GLOBAL_ORIGIN_DATA::deser(version, payload).map(Self::SET_GPS_GLOBAL_ORIGIN)
31765 }
31766 ATTITUDE_QUATERNION_DATA::ID => {
31767 ATTITUDE_QUATERNION_DATA::deser(version, payload).map(Self::ATTITUDE_QUATERNION)
31768 }
31769 TRAJECTORY_REPRESENTATION_BEZIER_DATA::ID => {
31770 TRAJECTORY_REPRESENTATION_BEZIER_DATA::deser(version, payload)
31771 .map(Self::TRAJECTORY_REPRESENTATION_BEZIER)
31772 }
31773 FUEL_STATUS_DATA::ID => {
31774 FUEL_STATUS_DATA::deser(version, payload).map(Self::FUEL_STATUS)
31775 }
31776 MISSION_CLEAR_ALL_DATA::ID => {
31777 MISSION_CLEAR_ALL_DATA::deser(version, payload).map(Self::MISSION_CLEAR_ALL)
31778 }
31779 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::ID => {
31780 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::deser(version, payload)
31781 .map(Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE)
31782 }
31783 LOGGING_DATA_ACKED_DATA::ID => {
31784 LOGGING_DATA_ACKED_DATA::deser(version, payload).map(Self::LOGGING_DATA_ACKED)
31785 }
31786 RESPONSE_EVENT_ERROR_DATA::ID => {
31787 RESPONSE_EVENT_ERROR_DATA::deser(version, payload).map(Self::RESPONSE_EVENT_ERROR)
31788 }
31789 SCALED_PRESSURE3_DATA::ID => {
31790 SCALED_PRESSURE3_DATA::deser(version, payload).map(Self::SCALED_PRESSURE3)
31791 }
31792 CANFD_FRAME_DATA::ID => {
31793 CANFD_FRAME_DATA::deser(version, payload).map(Self::CANFD_FRAME)
31794 }
31795 MISSION_REQUEST_INT_DATA::ID => {
31796 MISSION_REQUEST_INT_DATA::deser(version, payload).map(Self::MISSION_REQUEST_INT)
31797 }
31798 MAG_CAL_REPORT_DATA::ID => {
31799 MAG_CAL_REPORT_DATA::deser(version, payload).map(Self::MAG_CAL_REPORT)
31800 }
31801 COMMAND_ACK_DATA::ID => {
31802 COMMAND_ACK_DATA::deser(version, payload).map(Self::COMMAND_ACK)
31803 }
31804 MISSION_ITEM_REACHED_DATA::ID => {
31805 MISSION_ITEM_REACHED_DATA::deser(version, payload).map(Self::MISSION_ITEM_REACHED)
31806 }
31807 CHANGE_OPERATOR_CONTROL_ACK_DATA::ID => {
31808 CHANGE_OPERATOR_CONTROL_ACK_DATA::deser(version, payload)
31809 .map(Self::CHANGE_OPERATOR_CONTROL_ACK)
31810 }
31811 DEBUG_DATA::ID => DEBUG_DATA::deser(version, payload).map(Self::DEBUG),
31812 MISSION_COUNT_DATA::ID => {
31813 MISSION_COUNT_DATA::deser(version, payload).map(Self::MISSION_COUNT)
31814 }
31815 SERIAL_CONTROL_DATA::ID => {
31816 SERIAL_CONTROL_DATA::deser(version, payload).map(Self::SERIAL_CONTROL)
31817 }
31818 GPS2_RAW_DATA::ID => GPS2_RAW_DATA::deser(version, payload).map(Self::GPS2_RAW),
31819 FLIGHT_INFORMATION_DATA::ID => {
31820 FLIGHT_INFORMATION_DATA::deser(version, payload).map(Self::FLIGHT_INFORMATION)
31821 }
31822 GIMBAL_MANAGER_SET_ATTITUDE_DATA::ID => {
31823 GIMBAL_MANAGER_SET_ATTITUDE_DATA::deser(version, payload)
31824 .map(Self::GIMBAL_MANAGER_SET_ATTITUDE)
31825 }
31826 _ => Err(::mavlink_core::error::ParserError::UnknownMessage { id }),
31827 }
31828 }
31829 fn message_name(&self) -> &'static str {
31830 match self {
31831 Self::EVENT(..) => EVENT_DATA::NAME,
31832 Self::PROTOCOL_VERSION(..) => PROTOCOL_VERSION_DATA::NAME,
31833 Self::PARAM_VALUE(..) => PARAM_VALUE_DATA::NAME,
31834 Self::HIL_OPTICAL_FLOW(..) => HIL_OPTICAL_FLOW_DATA::NAME,
31835 Self::DISTANCE_SENSOR(..) => DISTANCE_SENSOR_DATA::NAME,
31836 Self::GPS_INPUT(..) => GPS_INPUT_DATA::NAME,
31837 Self::CAMERA_INFORMATION(..) => CAMERA_INFORMATION_DATA::NAME,
31838 Self::GIMBAL_DEVICE_INFORMATION(..) => GIMBAL_DEVICE_INFORMATION_DATA::NAME,
31839 Self::SYSTEM_TIME(..) => SYSTEM_TIME_DATA::NAME,
31840 Self::SET_HOME_POSITION(..) => SET_HOME_POSITION_DATA::NAME,
31841 Self::STATUSTEXT(..) => STATUSTEXT_DATA::NAME,
31842 Self::ATTITUDE(..) => ATTITUDE_DATA::NAME,
31843 Self::OPEN_DRONE_ID_AUTHENTICATION(..) => OPEN_DRONE_ID_AUTHENTICATION_DATA::NAME,
31844 Self::HIL_STATE_QUATERNION(..) => HIL_STATE_QUATERNION_DATA::NAME,
31845 Self::EXTENDED_SYS_STATE(..) => EXTENDED_SYS_STATE_DATA::NAME,
31846 Self::TRAJECTORY_REPRESENTATION_WAYPOINTS(..) => {
31847 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::NAME
31848 }
31849 Self::COLLISION(..) => COLLISION_DATA::NAME,
31850 Self::MISSION_ACK(..) => MISSION_ACK_DATA::NAME,
31851 Self::SET_POSITION_TARGET_GLOBAL_INT(..) => SET_POSITION_TARGET_GLOBAL_INT_DATA::NAME,
31852 Self::ESC_INFO(..) => ESC_INFO_DATA::NAME,
31853 Self::PLAY_TUNE_V2(..) => PLAY_TUNE_V2_DATA::NAME,
31854 Self::SERVO_OUTPUT_RAW(..) => SERVO_OUTPUT_RAW_DATA::NAME,
31855 Self::VICON_POSITION_ESTIMATE(..) => VICON_POSITION_ESTIMATE_DATA::NAME,
31856 Self::OPEN_DRONE_ID_SELF_ID(..) => OPEN_DRONE_ID_SELF_ID_DATA::NAME,
31857 Self::RC_CHANNELS_SCALED(..) => RC_CHANNELS_SCALED_DATA::NAME,
31858 Self::VIDEO_STREAM_STATUS(..) => VIDEO_STREAM_STATUS_DATA::NAME,
31859 Self::VISION_SPEED_ESTIMATE(..) => VISION_SPEED_ESTIMATE_DATA::NAME,
31860 Self::WIND_COV(..) => WIND_COV_DATA::NAME,
31861 Self::SCALED_IMU(..) => SCALED_IMU_DATA::NAME,
31862 Self::ORBIT_EXECUTION_STATUS(..) => ORBIT_EXECUTION_STATUS_DATA::NAME,
31863 Self::TERRAIN_REPORT(..) => TERRAIN_REPORT_DATA::NAME,
31864 Self::BATTERY_STATUS(..) => BATTERY_STATUS_DATA::NAME,
31865 Self::ESC_STATUS(..) => ESC_STATUS_DATA::NAME,
31866 Self::SCALED_IMU3(..) => SCALED_IMU3_DATA::NAME,
31867 Self::ACTUATOR_CONTROL_TARGET(..) => ACTUATOR_CONTROL_TARGET_DATA::NAME,
31868 Self::GPS_RAW_INT(..) => GPS_RAW_INT_DATA::NAME,
31869 Self::PARAM_SET(..) => PARAM_SET_DATA::NAME,
31870 Self::POSITION_TARGET_LOCAL_NED(..) => POSITION_TARGET_LOCAL_NED_DATA::NAME,
31871 Self::CURRENT_MODE(..) => CURRENT_MODE_DATA::NAME,
31872 Self::AIS_VESSEL(..) => AIS_VESSEL_DATA::NAME,
31873 Self::ENCAPSULATED_DATA(..) => ENCAPSULATED_DATA_DATA::NAME,
31874 Self::ILLUMINATOR_STATUS(..) => ILLUMINATOR_STATUS_DATA::NAME,
31875 Self::FOLLOW_TARGET(..) => FOLLOW_TARGET_DATA::NAME,
31876 Self::RC_CHANNELS_RAW(..) => RC_CHANNELS_RAW_DATA::NAME,
31877 Self::SET_ACTUATOR_CONTROL_TARGET(..) => SET_ACTUATOR_CONTROL_TARGET_DATA::NAME,
31878 Self::ADSB_VEHICLE(..) => ADSB_VEHICLE_DATA::NAME,
31879 Self::UAVCAN_NODE_INFO(..) => UAVCAN_NODE_INFO_DATA::NAME,
31880 Self::UAVCAN_NODE_STATUS(..) => UAVCAN_NODE_STATUS_DATA::NAME,
31881 Self::GLOBAL_VISION_POSITION_ESTIMATE(..) => GLOBAL_VISION_POSITION_ESTIMATE_DATA::NAME,
31882 Self::V2_EXTENSION(..) => V2_EXTENSION_DATA::NAME,
31883 Self::GPS_RTK(..) => GPS_RTK_DATA::NAME,
31884 Self::WIFI_CONFIG_AP(..) => WIFI_CONFIG_AP_DATA::NAME,
31885 Self::COMPONENT_INFORMATION(..) => COMPONENT_INFORMATION_DATA::NAME,
31886 Self::LOG_REQUEST_DATA(..) => LOG_REQUEST_DATA_DATA::NAME,
31887 Self::HIL_RC_INPUTS_RAW(..) => HIL_RC_INPUTS_RAW_DATA::NAME,
31888 Self::ACTUATOR_OUTPUT_STATUS(..) => ACTUATOR_OUTPUT_STATUS_DATA::NAME,
31889 Self::TIMESYNC(..) => TIMESYNC_DATA::NAME,
31890 Self::LOGGING_DATA(..) => LOGGING_DATA_DATA::NAME,
31891 Self::CAN_FILTER_MODIFY(..) => CAN_FILTER_MODIFY_DATA::NAME,
31892 Self::HYGROMETER_SENSOR(..) => HYGROMETER_SENSOR_DATA::NAME,
31893 Self::BATTERY_INFO(..) => BATTERY_INFO_DATA::NAME,
31894 Self::PARAM_EXT_SET(..) => PARAM_EXT_SET_DATA::NAME,
31895 Self::SAFETY_ALLOWED_AREA(..) => SAFETY_ALLOWED_AREA_DATA::NAME,
31896 Self::EFI_STATUS(..) => EFI_STATUS_DATA::NAME,
31897 Self::AUTOPILOT_VERSION(..) => AUTOPILOT_VERSION_DATA::NAME,
31898 Self::SET_MODE(..) => SET_MODE_DATA::NAME,
31899 Self::PARAM_MAP_RC(..) => PARAM_MAP_RC_DATA::NAME,
31900 Self::PARAM_EXT_REQUEST_READ(..) => PARAM_EXT_REQUEST_READ_DATA::NAME,
31901 Self::SCALED_IMU2(..) => SCALED_IMU2_DATA::NAME,
31902 Self::PLAY_TUNE(..) => PLAY_TUNE_DATA::NAME,
31903 Self::PARAM_REQUEST_LIST(..) => PARAM_REQUEST_LIST_DATA::NAME,
31904 Self::AUTH_KEY(..) => AUTH_KEY_DATA::NAME,
31905 Self::COMMAND_CANCEL(..) => COMMAND_CANCEL_DATA::NAME,
31906 Self::MANUAL_CONTROL(..) => MANUAL_CONTROL_DATA::NAME,
31907 Self::COMMAND_INT(..) => COMMAND_INT_DATA::NAME,
31908 Self::HIL_CONTROLS(..) => HIL_CONTROLS_DATA::NAME,
31909 Self::VISION_POSITION_ESTIMATE(..) => VISION_POSITION_ESTIMATE_DATA::NAME,
31910 Self::GPS_RTCM_DATA(..) => GPS_RTCM_DATA_DATA::NAME,
31911 Self::MEMORY_VECT(..) => MEMORY_VECT_DATA::NAME,
31912 Self::BUTTON_CHANGE(..) => BUTTON_CHANGE_DATA::NAME,
31913 Self::UTM_GLOBAL_POSITION(..) => UTM_GLOBAL_POSITION_DATA::NAME,
31914 Self::WHEEL_DISTANCE(..) => WHEEL_DISTANCE_DATA::NAME,
31915 Self::HIGHRES_IMU(..) => HIGHRES_IMU_DATA::NAME,
31916 Self::CAMERA_TRIGGER(..) => CAMERA_TRIGGER_DATA::NAME,
31917 Self::GPS_INJECT_DATA(..) => GPS_INJECT_DATA_DATA::NAME,
31918 Self::CAMERA_THERMAL_RANGE(..) => CAMERA_THERMAL_RANGE_DATA::NAME,
31919 Self::RAW_RPM(..) => RAW_RPM_DATA::NAME,
31920 Self::REQUEST_EVENT(..) => REQUEST_EVENT_DATA::NAME,
31921 Self::LOCAL_POSITION_NED_COV(..) => LOCAL_POSITION_NED_COV_DATA::NAME,
31922 Self::GLOBAL_POSITION_INT_COV(..) => GLOBAL_POSITION_INT_COV_DATA::NAME,
31923 Self::LOCAL_POSITION_NED(..) => LOCAL_POSITION_NED_DATA::NAME,
31924 Self::REQUEST_DATA_STREAM(..) => REQUEST_DATA_STREAM_DATA::NAME,
31925 Self::TERRAIN_DATA(..) => TERRAIN_DATA_DATA::NAME,
31926 Self::CAMERA_FOV_STATUS(..) => CAMERA_FOV_STATUS_DATA::NAME,
31927 Self::TERRAIN_CHECK(..) => TERRAIN_CHECK_DATA::NAME,
31928 Self::HOME_POSITION(..) => HOME_POSITION_DATA::NAME,
31929 Self::HIL_SENSOR(..) => HIL_SENSOR_DATA::NAME,
31930 Self::POWER_STATUS(..) => POWER_STATUS_DATA::NAME,
31931 Self::HIL_ACTUATOR_CONTROLS(..) => HIL_ACTUATOR_CONTROLS_DATA::NAME,
31932 Self::GLOBAL_POSITION_INT(..) => GLOBAL_POSITION_INT_DATA::NAME,
31933 Self::CELLULAR_CONFIG(..) => CELLULAR_CONFIG_DATA::NAME,
31934 Self::AVAILABLE_MODES_MONITOR(..) => AVAILABLE_MODES_MONITOR_DATA::NAME,
31935 Self::GPS_STATUS(..) => GPS_STATUS_DATA::NAME,
31936 Self::SCALED_PRESSURE(..) => SCALED_PRESSURE_DATA::NAME,
31937 Self::OPTICAL_FLOW(..) => OPTICAL_FLOW_DATA::NAME,
31938 Self::OPEN_DRONE_ID_ARM_STATUS(..) => OPEN_DRONE_ID_ARM_STATUS_DATA::NAME,
31939 Self::RC_CHANNELS_OVERRIDE(..) => RC_CHANNELS_OVERRIDE_DATA::NAME,
31940 Self::LOG_DATA(..) => LOG_DATA_DATA::NAME,
31941 Self::MISSION_REQUEST_LIST(..) => MISSION_REQUEST_LIST_DATA::NAME,
31942 Self::ATTITUDE_QUATERNION_COV(..) => ATTITUDE_QUATERNION_COV_DATA::NAME,
31943 Self::POSITION_TARGET_GLOBAL_INT(..) => POSITION_TARGET_GLOBAL_INT_DATA::NAME,
31944 Self::GPS2_RTK(..) => GPS2_RTK_DATA::NAME,
31945 Self::RESOURCE_REQUEST(..) => RESOURCE_REQUEST_DATA::NAME,
31946 Self::ESTIMATOR_STATUS(..) => ESTIMATOR_STATUS_DATA::NAME,
31947 Self::ONBOARD_COMPUTER_STATUS(..) => ONBOARD_COMPUTER_STATUS_DATA::NAME,
31948 Self::LINK_NODE_STATUS(..) => LINK_NODE_STATUS_DATA::NAME,
31949 Self::CONTROL_SYSTEM_STATE(..) => CONTROL_SYSTEM_STATE_DATA::NAME,
31950 Self::MESSAGE_INTERVAL(..) => MESSAGE_INTERVAL_DATA::NAME,
31951 Self::ODOMETRY(..) => ODOMETRY_DATA::NAME,
31952 Self::VIDEO_STREAM_INFORMATION(..) => VIDEO_STREAM_INFORMATION_DATA::NAME,
31953 Self::CAMERA_TRACKING_GEO_STATUS(..) => CAMERA_TRACKING_GEO_STATUS_DATA::NAME,
31954 Self::COMPONENT_METADATA(..) => COMPONENT_METADATA_DATA::NAME,
31955 Self::RC_CHANNELS(..) => RC_CHANNELS_DATA::NAME,
31956 Self::ATTITUDE_TARGET(..) => ATTITUDE_TARGET_DATA::NAME,
31957 Self::CAMERA_TRACKING_IMAGE_STATUS(..) => CAMERA_TRACKING_IMAGE_STATUS_DATA::NAME,
31958 Self::MISSION_CURRENT(..) => MISSION_CURRENT_DATA::NAME,
31959 Self::LOG_REQUEST_LIST(..) => LOG_REQUEST_LIST_DATA::NAME,
31960 Self::ISBD_LINK_STATUS(..) => ISBD_LINK_STATUS_DATA::NAME,
31961 Self::PARAM_EXT_ACK(..) => PARAM_EXT_ACK_DATA::NAME,
31962 Self::SETUP_SIGNING(..) => SETUP_SIGNING_DATA::NAME,
31963 Self::AVAILABLE_MODES(..) => AVAILABLE_MODES_DATA::NAME,
31964 Self::SAFETY_SET_ALLOWED_AREA(..) => SAFETY_SET_ALLOWED_AREA_DATA::NAME,
31965 Self::SET_ATTITUDE_TARGET(..) => SET_ATTITUDE_TARGET_DATA::NAME,
31966 Self::FENCE_STATUS(..) => FENCE_STATUS_DATA::NAME,
31967 Self::LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET(..) => {
31968 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::NAME
31969 }
31970 Self::SMART_BATTERY_INFO(..) => SMART_BATTERY_INFO_DATA::NAME,
31971 Self::OPEN_DRONE_ID_MESSAGE_PACK(..) => OPEN_DRONE_ID_MESSAGE_PACK_DATA::NAME,
31972 Self::TIME_ESTIMATE_TO_TARGET(..) => TIME_ESTIMATE_TO_TARGET_DATA::NAME,
31973 Self::CAMERA_CAPTURE_STATUS(..) => CAMERA_CAPTURE_STATUS_DATA::NAME,
31974 Self::ALTITUDE(..) => ALTITUDE_DATA::NAME,
31975 Self::DEBUG_VECT(..) => DEBUG_VECT_DATA::NAME,
31976 Self::GIMBAL_MANAGER_SET_PITCHYAW(..) => GIMBAL_MANAGER_SET_PITCHYAW_DATA::NAME,
31977 Self::CAMERA_IMAGE_CAPTURED(..) => CAMERA_IMAGE_CAPTURED_DATA::NAME,
31978 Self::COMMAND_LONG(..) => COMMAND_LONG_DATA::NAME,
31979 Self::PARAM_EXT_REQUEST_LIST(..) => PARAM_EXT_REQUEST_LIST_DATA::NAME,
31980 Self::PARAM_EXT_VALUE(..) => PARAM_EXT_VALUE_DATA::NAME,
31981 Self::GIMBAL_MANAGER_INFORMATION(..) => GIMBAL_MANAGER_INFORMATION_DATA::NAME,
31982 Self::OPEN_DRONE_ID_BASIC_ID(..) => OPEN_DRONE_ID_BASIC_ID_DATA::NAME,
31983 Self::SCALED_PRESSURE2(..) => SCALED_PRESSURE2_DATA::NAME,
31984 Self::LANDING_TARGET(..) => LANDING_TARGET_DATA::NAME,
31985 Self::OPEN_DRONE_ID_SYSTEM_UPDATE(..) => OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::NAME,
31986 Self::MISSION_REQUEST_PARTIAL_LIST(..) => MISSION_REQUEST_PARTIAL_LIST_DATA::NAME,
31987 Self::VFR_HUD(..) => VFR_HUD_DATA::NAME,
31988 Self::SYS_STATUS(..) => SYS_STATUS_DATA::NAME,
31989 Self::GPS_GLOBAL_ORIGIN(..) => GPS_GLOBAL_ORIGIN_DATA::NAME,
31990 Self::GIMBAL_MANAGER_STATUS(..) => GIMBAL_MANAGER_STATUS_DATA::NAME,
31991 Self::LOG_ERASE(..) => LOG_ERASE_DATA::NAME,
31992 Self::PARAM_REQUEST_READ(..) => PARAM_REQUEST_READ_DATA::NAME,
31993 Self::HIL_STATE(..) => HIL_STATE_DATA::NAME,
31994 Self::CURRENT_EVENT_SEQUENCE(..) => CURRENT_EVENT_SEQUENCE_DATA::NAME,
31995 Self::LOG_ENTRY(..) => LOG_ENTRY_DATA::NAME,
31996 Self::MISSION_ITEM_INT(..) => MISSION_ITEM_INT_DATA::NAME,
31997 Self::HIGH_LATENCY2(..) => HIGH_LATENCY2_DATA::NAME,
31998 Self::CELLULAR_STATUS(..) => CELLULAR_STATUS_DATA::NAME,
31999 Self::MISSION_ITEM(..) => MISSION_ITEM_DATA::NAME,
32000 Self::NAV_CONTROLLER_OUTPUT(..) => NAV_CONTROLLER_OUTPUT_DATA::NAME,
32001 Self::GIMBAL_DEVICE_ATTITUDE_STATUS(..) => GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::NAME,
32002 Self::STORAGE_INFORMATION(..) => STORAGE_INFORMATION_DATA::NAME,
32003 Self::RADIO_STATUS(..) => RADIO_STATUS_DATA::NAME,
32004 Self::COMPONENT_INFORMATION_BASIC(..) => COMPONENT_INFORMATION_BASIC_DATA::NAME,
32005 Self::NAMED_VALUE_INT(..) => NAMED_VALUE_INT_DATA::NAME,
32006 Self::LOG_REQUEST_END(..) => LOG_REQUEST_END_DATA::NAME,
32007 Self::MISSION_REQUEST(..) => MISSION_REQUEST_DATA::NAME,
32008 Self::SET_POSITION_TARGET_LOCAL_NED(..) => SET_POSITION_TARGET_LOCAL_NED_DATA::NAME,
32009 Self::LOGGING_ACK(..) => LOGGING_ACK_DATA::NAME,
32010 Self::CAN_FRAME(..) => CAN_FRAME_DATA::NAME,
32011 Self::HIGH_LATENCY(..) => HIGH_LATENCY_DATA::NAME,
32012 Self::VIBRATION(..) => VIBRATION_DATA::NAME,
32013 Self::CHANGE_OPERATOR_CONTROL(..) => CHANGE_OPERATOR_CONTROL_DATA::NAME,
32014 Self::MANUAL_SETPOINT(..) => MANUAL_SETPOINT_DATA::NAME,
32015 Self::MOUNT_ORIENTATION(..) => MOUNT_ORIENTATION_DATA::NAME,
32016 Self::MISSION_SET_CURRENT(..) => MISSION_SET_CURRENT_DATA::NAME,
32017 Self::RAW_IMU(..) => RAW_IMU_DATA::NAME,
32018 Self::RAW_PRESSURE(..) => RAW_PRESSURE_DATA::NAME,
32019 Self::DATA_STREAM(..) => DATA_STREAM_DATA::NAME,
32020 Self::OPEN_DRONE_ID_LOCATION(..) => OPEN_DRONE_ID_LOCATION_DATA::NAME,
32021 Self::TUNNEL(..) => TUNNEL_DATA::NAME,
32022 Self::NAMED_VALUE_FLOAT(..) => NAMED_VALUE_FLOAT_DATA::NAME,
32023 Self::SIM_STATE(..) => SIM_STATE_DATA::NAME,
32024 Self::OPEN_DRONE_ID_SYSTEM(..) => OPEN_DRONE_ID_SYSTEM_DATA::NAME,
32025 Self::OPEN_DRONE_ID_OPERATOR_ID(..) => OPEN_DRONE_ID_OPERATOR_ID_DATA::NAME,
32026 Self::MISSION_WRITE_PARTIAL_LIST(..) => MISSION_WRITE_PARTIAL_LIST_DATA::NAME,
32027 Self::DEBUG_FLOAT_ARRAY(..) => DEBUG_FLOAT_ARRAY_DATA::NAME,
32028 Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL(..) => {
32029 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::NAME
32030 }
32031 Self::PING(..) => PING_DATA::NAME,
32032 Self::CAMERA_SETTINGS(..) => CAMERA_SETTINGS_DATA::NAME,
32033 Self::TERRAIN_REQUEST(..) => TERRAIN_REQUEST_DATA::NAME,
32034 Self::GIMBAL_DEVICE_SET_ATTITUDE(..) => GIMBAL_DEVICE_SET_ATTITUDE_DATA::NAME,
32035 Self::ATT_POS_MOCAP(..) => ATT_POS_MOCAP_DATA::NAME,
32036 Self::HEARTBEAT(..) => HEARTBEAT_DATA::NAME,
32037 Self::OBSTACLE_DISTANCE(..) => OBSTACLE_DISTANCE_DATA::NAME,
32038 Self::OPTICAL_FLOW_RAD(..) => OPTICAL_FLOW_RAD_DATA::NAME,
32039 Self::HIL_GPS(..) => HIL_GPS_DATA::NAME,
32040 Self::WINCH_STATUS(..) => WINCH_STATUS_DATA::NAME,
32041 Self::GENERATOR_STATUS(..) => GENERATOR_STATUS_DATA::NAME,
32042 Self::FILE_TRANSFER_PROTOCOL(..) => FILE_TRANSFER_PROTOCOL_DATA::NAME,
32043 Self::DATA_TRANSMISSION_HANDSHAKE(..) => DATA_TRANSMISSION_HANDSHAKE_DATA::NAME,
32044 Self::SUPPORTED_TUNES(..) => SUPPORTED_TUNES_DATA::NAME,
32045 Self::SET_GPS_GLOBAL_ORIGIN(..) => SET_GPS_GLOBAL_ORIGIN_DATA::NAME,
32046 Self::ATTITUDE_QUATERNION(..) => ATTITUDE_QUATERNION_DATA::NAME,
32047 Self::TRAJECTORY_REPRESENTATION_BEZIER(..) => {
32048 TRAJECTORY_REPRESENTATION_BEZIER_DATA::NAME
32049 }
32050 Self::FUEL_STATUS(..) => FUEL_STATUS_DATA::NAME,
32051 Self::MISSION_CLEAR_ALL(..) => MISSION_CLEAR_ALL_DATA::NAME,
32052 Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(..) => {
32053 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::NAME
32054 }
32055 Self::LOGGING_DATA_ACKED(..) => LOGGING_DATA_ACKED_DATA::NAME,
32056 Self::RESPONSE_EVENT_ERROR(..) => RESPONSE_EVENT_ERROR_DATA::NAME,
32057 Self::SCALED_PRESSURE3(..) => SCALED_PRESSURE3_DATA::NAME,
32058 Self::CANFD_FRAME(..) => CANFD_FRAME_DATA::NAME,
32059 Self::MISSION_REQUEST_INT(..) => MISSION_REQUEST_INT_DATA::NAME,
32060 Self::MAG_CAL_REPORT(..) => MAG_CAL_REPORT_DATA::NAME,
32061 Self::COMMAND_ACK(..) => COMMAND_ACK_DATA::NAME,
32062 Self::MISSION_ITEM_REACHED(..) => MISSION_ITEM_REACHED_DATA::NAME,
32063 Self::CHANGE_OPERATOR_CONTROL_ACK(..) => CHANGE_OPERATOR_CONTROL_ACK_DATA::NAME,
32064 Self::DEBUG(..) => DEBUG_DATA::NAME,
32065 Self::MISSION_COUNT(..) => MISSION_COUNT_DATA::NAME,
32066 Self::SERIAL_CONTROL(..) => SERIAL_CONTROL_DATA::NAME,
32067 Self::GPS2_RAW(..) => GPS2_RAW_DATA::NAME,
32068 Self::FLIGHT_INFORMATION(..) => FLIGHT_INFORMATION_DATA::NAME,
32069 Self::GIMBAL_MANAGER_SET_ATTITUDE(..) => GIMBAL_MANAGER_SET_ATTITUDE_DATA::NAME,
32070 }
32071 }
32072 fn message_id(&self) -> u32 {
32073 match self {
32074 Self::EVENT(..) => EVENT_DATA::ID,
32075 Self::PROTOCOL_VERSION(..) => PROTOCOL_VERSION_DATA::ID,
32076 Self::PARAM_VALUE(..) => PARAM_VALUE_DATA::ID,
32077 Self::HIL_OPTICAL_FLOW(..) => HIL_OPTICAL_FLOW_DATA::ID,
32078 Self::DISTANCE_SENSOR(..) => DISTANCE_SENSOR_DATA::ID,
32079 Self::GPS_INPUT(..) => GPS_INPUT_DATA::ID,
32080 Self::CAMERA_INFORMATION(..) => CAMERA_INFORMATION_DATA::ID,
32081 Self::GIMBAL_DEVICE_INFORMATION(..) => GIMBAL_DEVICE_INFORMATION_DATA::ID,
32082 Self::SYSTEM_TIME(..) => SYSTEM_TIME_DATA::ID,
32083 Self::SET_HOME_POSITION(..) => SET_HOME_POSITION_DATA::ID,
32084 Self::STATUSTEXT(..) => STATUSTEXT_DATA::ID,
32085 Self::ATTITUDE(..) => ATTITUDE_DATA::ID,
32086 Self::OPEN_DRONE_ID_AUTHENTICATION(..) => OPEN_DRONE_ID_AUTHENTICATION_DATA::ID,
32087 Self::HIL_STATE_QUATERNION(..) => HIL_STATE_QUATERNION_DATA::ID,
32088 Self::EXTENDED_SYS_STATE(..) => EXTENDED_SYS_STATE_DATA::ID,
32089 Self::TRAJECTORY_REPRESENTATION_WAYPOINTS(..) => {
32090 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::ID
32091 }
32092 Self::COLLISION(..) => COLLISION_DATA::ID,
32093 Self::MISSION_ACK(..) => MISSION_ACK_DATA::ID,
32094 Self::SET_POSITION_TARGET_GLOBAL_INT(..) => SET_POSITION_TARGET_GLOBAL_INT_DATA::ID,
32095 Self::ESC_INFO(..) => ESC_INFO_DATA::ID,
32096 Self::PLAY_TUNE_V2(..) => PLAY_TUNE_V2_DATA::ID,
32097 Self::SERVO_OUTPUT_RAW(..) => SERVO_OUTPUT_RAW_DATA::ID,
32098 Self::VICON_POSITION_ESTIMATE(..) => VICON_POSITION_ESTIMATE_DATA::ID,
32099 Self::OPEN_DRONE_ID_SELF_ID(..) => OPEN_DRONE_ID_SELF_ID_DATA::ID,
32100 Self::RC_CHANNELS_SCALED(..) => RC_CHANNELS_SCALED_DATA::ID,
32101 Self::VIDEO_STREAM_STATUS(..) => VIDEO_STREAM_STATUS_DATA::ID,
32102 Self::VISION_SPEED_ESTIMATE(..) => VISION_SPEED_ESTIMATE_DATA::ID,
32103 Self::WIND_COV(..) => WIND_COV_DATA::ID,
32104 Self::SCALED_IMU(..) => SCALED_IMU_DATA::ID,
32105 Self::ORBIT_EXECUTION_STATUS(..) => ORBIT_EXECUTION_STATUS_DATA::ID,
32106 Self::TERRAIN_REPORT(..) => TERRAIN_REPORT_DATA::ID,
32107 Self::BATTERY_STATUS(..) => BATTERY_STATUS_DATA::ID,
32108 Self::ESC_STATUS(..) => ESC_STATUS_DATA::ID,
32109 Self::SCALED_IMU3(..) => SCALED_IMU3_DATA::ID,
32110 Self::ACTUATOR_CONTROL_TARGET(..) => ACTUATOR_CONTROL_TARGET_DATA::ID,
32111 Self::GPS_RAW_INT(..) => GPS_RAW_INT_DATA::ID,
32112 Self::PARAM_SET(..) => PARAM_SET_DATA::ID,
32113 Self::POSITION_TARGET_LOCAL_NED(..) => POSITION_TARGET_LOCAL_NED_DATA::ID,
32114 Self::CURRENT_MODE(..) => CURRENT_MODE_DATA::ID,
32115 Self::AIS_VESSEL(..) => AIS_VESSEL_DATA::ID,
32116 Self::ENCAPSULATED_DATA(..) => ENCAPSULATED_DATA_DATA::ID,
32117 Self::ILLUMINATOR_STATUS(..) => ILLUMINATOR_STATUS_DATA::ID,
32118 Self::FOLLOW_TARGET(..) => FOLLOW_TARGET_DATA::ID,
32119 Self::RC_CHANNELS_RAW(..) => RC_CHANNELS_RAW_DATA::ID,
32120 Self::SET_ACTUATOR_CONTROL_TARGET(..) => SET_ACTUATOR_CONTROL_TARGET_DATA::ID,
32121 Self::ADSB_VEHICLE(..) => ADSB_VEHICLE_DATA::ID,
32122 Self::UAVCAN_NODE_INFO(..) => UAVCAN_NODE_INFO_DATA::ID,
32123 Self::UAVCAN_NODE_STATUS(..) => UAVCAN_NODE_STATUS_DATA::ID,
32124 Self::GLOBAL_VISION_POSITION_ESTIMATE(..) => GLOBAL_VISION_POSITION_ESTIMATE_DATA::ID,
32125 Self::V2_EXTENSION(..) => V2_EXTENSION_DATA::ID,
32126 Self::GPS_RTK(..) => GPS_RTK_DATA::ID,
32127 Self::WIFI_CONFIG_AP(..) => WIFI_CONFIG_AP_DATA::ID,
32128 Self::COMPONENT_INFORMATION(..) => COMPONENT_INFORMATION_DATA::ID,
32129 Self::LOG_REQUEST_DATA(..) => LOG_REQUEST_DATA_DATA::ID,
32130 Self::HIL_RC_INPUTS_RAW(..) => HIL_RC_INPUTS_RAW_DATA::ID,
32131 Self::ACTUATOR_OUTPUT_STATUS(..) => ACTUATOR_OUTPUT_STATUS_DATA::ID,
32132 Self::TIMESYNC(..) => TIMESYNC_DATA::ID,
32133 Self::LOGGING_DATA(..) => LOGGING_DATA_DATA::ID,
32134 Self::CAN_FILTER_MODIFY(..) => CAN_FILTER_MODIFY_DATA::ID,
32135 Self::HYGROMETER_SENSOR(..) => HYGROMETER_SENSOR_DATA::ID,
32136 Self::BATTERY_INFO(..) => BATTERY_INFO_DATA::ID,
32137 Self::PARAM_EXT_SET(..) => PARAM_EXT_SET_DATA::ID,
32138 Self::SAFETY_ALLOWED_AREA(..) => SAFETY_ALLOWED_AREA_DATA::ID,
32139 Self::EFI_STATUS(..) => EFI_STATUS_DATA::ID,
32140 Self::AUTOPILOT_VERSION(..) => AUTOPILOT_VERSION_DATA::ID,
32141 Self::SET_MODE(..) => SET_MODE_DATA::ID,
32142 Self::PARAM_MAP_RC(..) => PARAM_MAP_RC_DATA::ID,
32143 Self::PARAM_EXT_REQUEST_READ(..) => PARAM_EXT_REQUEST_READ_DATA::ID,
32144 Self::SCALED_IMU2(..) => SCALED_IMU2_DATA::ID,
32145 Self::PLAY_TUNE(..) => PLAY_TUNE_DATA::ID,
32146 Self::PARAM_REQUEST_LIST(..) => PARAM_REQUEST_LIST_DATA::ID,
32147 Self::AUTH_KEY(..) => AUTH_KEY_DATA::ID,
32148 Self::COMMAND_CANCEL(..) => COMMAND_CANCEL_DATA::ID,
32149 Self::MANUAL_CONTROL(..) => MANUAL_CONTROL_DATA::ID,
32150 Self::COMMAND_INT(..) => COMMAND_INT_DATA::ID,
32151 Self::HIL_CONTROLS(..) => HIL_CONTROLS_DATA::ID,
32152 Self::VISION_POSITION_ESTIMATE(..) => VISION_POSITION_ESTIMATE_DATA::ID,
32153 Self::GPS_RTCM_DATA(..) => GPS_RTCM_DATA_DATA::ID,
32154 Self::MEMORY_VECT(..) => MEMORY_VECT_DATA::ID,
32155 Self::BUTTON_CHANGE(..) => BUTTON_CHANGE_DATA::ID,
32156 Self::UTM_GLOBAL_POSITION(..) => UTM_GLOBAL_POSITION_DATA::ID,
32157 Self::WHEEL_DISTANCE(..) => WHEEL_DISTANCE_DATA::ID,
32158 Self::HIGHRES_IMU(..) => HIGHRES_IMU_DATA::ID,
32159 Self::CAMERA_TRIGGER(..) => CAMERA_TRIGGER_DATA::ID,
32160 Self::GPS_INJECT_DATA(..) => GPS_INJECT_DATA_DATA::ID,
32161 Self::CAMERA_THERMAL_RANGE(..) => CAMERA_THERMAL_RANGE_DATA::ID,
32162 Self::RAW_RPM(..) => RAW_RPM_DATA::ID,
32163 Self::REQUEST_EVENT(..) => REQUEST_EVENT_DATA::ID,
32164 Self::LOCAL_POSITION_NED_COV(..) => LOCAL_POSITION_NED_COV_DATA::ID,
32165 Self::GLOBAL_POSITION_INT_COV(..) => GLOBAL_POSITION_INT_COV_DATA::ID,
32166 Self::LOCAL_POSITION_NED(..) => LOCAL_POSITION_NED_DATA::ID,
32167 Self::REQUEST_DATA_STREAM(..) => REQUEST_DATA_STREAM_DATA::ID,
32168 Self::TERRAIN_DATA(..) => TERRAIN_DATA_DATA::ID,
32169 Self::CAMERA_FOV_STATUS(..) => CAMERA_FOV_STATUS_DATA::ID,
32170 Self::TERRAIN_CHECK(..) => TERRAIN_CHECK_DATA::ID,
32171 Self::HOME_POSITION(..) => HOME_POSITION_DATA::ID,
32172 Self::HIL_SENSOR(..) => HIL_SENSOR_DATA::ID,
32173 Self::POWER_STATUS(..) => POWER_STATUS_DATA::ID,
32174 Self::HIL_ACTUATOR_CONTROLS(..) => HIL_ACTUATOR_CONTROLS_DATA::ID,
32175 Self::GLOBAL_POSITION_INT(..) => GLOBAL_POSITION_INT_DATA::ID,
32176 Self::CELLULAR_CONFIG(..) => CELLULAR_CONFIG_DATA::ID,
32177 Self::AVAILABLE_MODES_MONITOR(..) => AVAILABLE_MODES_MONITOR_DATA::ID,
32178 Self::GPS_STATUS(..) => GPS_STATUS_DATA::ID,
32179 Self::SCALED_PRESSURE(..) => SCALED_PRESSURE_DATA::ID,
32180 Self::OPTICAL_FLOW(..) => OPTICAL_FLOW_DATA::ID,
32181 Self::OPEN_DRONE_ID_ARM_STATUS(..) => OPEN_DRONE_ID_ARM_STATUS_DATA::ID,
32182 Self::RC_CHANNELS_OVERRIDE(..) => RC_CHANNELS_OVERRIDE_DATA::ID,
32183 Self::LOG_DATA(..) => LOG_DATA_DATA::ID,
32184 Self::MISSION_REQUEST_LIST(..) => MISSION_REQUEST_LIST_DATA::ID,
32185 Self::ATTITUDE_QUATERNION_COV(..) => ATTITUDE_QUATERNION_COV_DATA::ID,
32186 Self::POSITION_TARGET_GLOBAL_INT(..) => POSITION_TARGET_GLOBAL_INT_DATA::ID,
32187 Self::GPS2_RTK(..) => GPS2_RTK_DATA::ID,
32188 Self::RESOURCE_REQUEST(..) => RESOURCE_REQUEST_DATA::ID,
32189 Self::ESTIMATOR_STATUS(..) => ESTIMATOR_STATUS_DATA::ID,
32190 Self::ONBOARD_COMPUTER_STATUS(..) => ONBOARD_COMPUTER_STATUS_DATA::ID,
32191 Self::LINK_NODE_STATUS(..) => LINK_NODE_STATUS_DATA::ID,
32192 Self::CONTROL_SYSTEM_STATE(..) => CONTROL_SYSTEM_STATE_DATA::ID,
32193 Self::MESSAGE_INTERVAL(..) => MESSAGE_INTERVAL_DATA::ID,
32194 Self::ODOMETRY(..) => ODOMETRY_DATA::ID,
32195 Self::VIDEO_STREAM_INFORMATION(..) => VIDEO_STREAM_INFORMATION_DATA::ID,
32196 Self::CAMERA_TRACKING_GEO_STATUS(..) => CAMERA_TRACKING_GEO_STATUS_DATA::ID,
32197 Self::COMPONENT_METADATA(..) => COMPONENT_METADATA_DATA::ID,
32198 Self::RC_CHANNELS(..) => RC_CHANNELS_DATA::ID,
32199 Self::ATTITUDE_TARGET(..) => ATTITUDE_TARGET_DATA::ID,
32200 Self::CAMERA_TRACKING_IMAGE_STATUS(..) => CAMERA_TRACKING_IMAGE_STATUS_DATA::ID,
32201 Self::MISSION_CURRENT(..) => MISSION_CURRENT_DATA::ID,
32202 Self::LOG_REQUEST_LIST(..) => LOG_REQUEST_LIST_DATA::ID,
32203 Self::ISBD_LINK_STATUS(..) => ISBD_LINK_STATUS_DATA::ID,
32204 Self::PARAM_EXT_ACK(..) => PARAM_EXT_ACK_DATA::ID,
32205 Self::SETUP_SIGNING(..) => SETUP_SIGNING_DATA::ID,
32206 Self::AVAILABLE_MODES(..) => AVAILABLE_MODES_DATA::ID,
32207 Self::SAFETY_SET_ALLOWED_AREA(..) => SAFETY_SET_ALLOWED_AREA_DATA::ID,
32208 Self::SET_ATTITUDE_TARGET(..) => SET_ATTITUDE_TARGET_DATA::ID,
32209 Self::FENCE_STATUS(..) => FENCE_STATUS_DATA::ID,
32210 Self::LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET(..) => {
32211 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::ID
32212 }
32213 Self::SMART_BATTERY_INFO(..) => SMART_BATTERY_INFO_DATA::ID,
32214 Self::OPEN_DRONE_ID_MESSAGE_PACK(..) => OPEN_DRONE_ID_MESSAGE_PACK_DATA::ID,
32215 Self::TIME_ESTIMATE_TO_TARGET(..) => TIME_ESTIMATE_TO_TARGET_DATA::ID,
32216 Self::CAMERA_CAPTURE_STATUS(..) => CAMERA_CAPTURE_STATUS_DATA::ID,
32217 Self::ALTITUDE(..) => ALTITUDE_DATA::ID,
32218 Self::DEBUG_VECT(..) => DEBUG_VECT_DATA::ID,
32219 Self::GIMBAL_MANAGER_SET_PITCHYAW(..) => GIMBAL_MANAGER_SET_PITCHYAW_DATA::ID,
32220 Self::CAMERA_IMAGE_CAPTURED(..) => CAMERA_IMAGE_CAPTURED_DATA::ID,
32221 Self::COMMAND_LONG(..) => COMMAND_LONG_DATA::ID,
32222 Self::PARAM_EXT_REQUEST_LIST(..) => PARAM_EXT_REQUEST_LIST_DATA::ID,
32223 Self::PARAM_EXT_VALUE(..) => PARAM_EXT_VALUE_DATA::ID,
32224 Self::GIMBAL_MANAGER_INFORMATION(..) => GIMBAL_MANAGER_INFORMATION_DATA::ID,
32225 Self::OPEN_DRONE_ID_BASIC_ID(..) => OPEN_DRONE_ID_BASIC_ID_DATA::ID,
32226 Self::SCALED_PRESSURE2(..) => SCALED_PRESSURE2_DATA::ID,
32227 Self::LANDING_TARGET(..) => LANDING_TARGET_DATA::ID,
32228 Self::OPEN_DRONE_ID_SYSTEM_UPDATE(..) => OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::ID,
32229 Self::MISSION_REQUEST_PARTIAL_LIST(..) => MISSION_REQUEST_PARTIAL_LIST_DATA::ID,
32230 Self::VFR_HUD(..) => VFR_HUD_DATA::ID,
32231 Self::SYS_STATUS(..) => SYS_STATUS_DATA::ID,
32232 Self::GPS_GLOBAL_ORIGIN(..) => GPS_GLOBAL_ORIGIN_DATA::ID,
32233 Self::GIMBAL_MANAGER_STATUS(..) => GIMBAL_MANAGER_STATUS_DATA::ID,
32234 Self::LOG_ERASE(..) => LOG_ERASE_DATA::ID,
32235 Self::PARAM_REQUEST_READ(..) => PARAM_REQUEST_READ_DATA::ID,
32236 Self::HIL_STATE(..) => HIL_STATE_DATA::ID,
32237 Self::CURRENT_EVENT_SEQUENCE(..) => CURRENT_EVENT_SEQUENCE_DATA::ID,
32238 Self::LOG_ENTRY(..) => LOG_ENTRY_DATA::ID,
32239 Self::MISSION_ITEM_INT(..) => MISSION_ITEM_INT_DATA::ID,
32240 Self::HIGH_LATENCY2(..) => HIGH_LATENCY2_DATA::ID,
32241 Self::CELLULAR_STATUS(..) => CELLULAR_STATUS_DATA::ID,
32242 Self::MISSION_ITEM(..) => MISSION_ITEM_DATA::ID,
32243 Self::NAV_CONTROLLER_OUTPUT(..) => NAV_CONTROLLER_OUTPUT_DATA::ID,
32244 Self::GIMBAL_DEVICE_ATTITUDE_STATUS(..) => GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::ID,
32245 Self::STORAGE_INFORMATION(..) => STORAGE_INFORMATION_DATA::ID,
32246 Self::RADIO_STATUS(..) => RADIO_STATUS_DATA::ID,
32247 Self::COMPONENT_INFORMATION_BASIC(..) => COMPONENT_INFORMATION_BASIC_DATA::ID,
32248 Self::NAMED_VALUE_INT(..) => NAMED_VALUE_INT_DATA::ID,
32249 Self::LOG_REQUEST_END(..) => LOG_REQUEST_END_DATA::ID,
32250 Self::MISSION_REQUEST(..) => MISSION_REQUEST_DATA::ID,
32251 Self::SET_POSITION_TARGET_LOCAL_NED(..) => SET_POSITION_TARGET_LOCAL_NED_DATA::ID,
32252 Self::LOGGING_ACK(..) => LOGGING_ACK_DATA::ID,
32253 Self::CAN_FRAME(..) => CAN_FRAME_DATA::ID,
32254 Self::HIGH_LATENCY(..) => HIGH_LATENCY_DATA::ID,
32255 Self::VIBRATION(..) => VIBRATION_DATA::ID,
32256 Self::CHANGE_OPERATOR_CONTROL(..) => CHANGE_OPERATOR_CONTROL_DATA::ID,
32257 Self::MANUAL_SETPOINT(..) => MANUAL_SETPOINT_DATA::ID,
32258 Self::MOUNT_ORIENTATION(..) => MOUNT_ORIENTATION_DATA::ID,
32259 Self::MISSION_SET_CURRENT(..) => MISSION_SET_CURRENT_DATA::ID,
32260 Self::RAW_IMU(..) => RAW_IMU_DATA::ID,
32261 Self::RAW_PRESSURE(..) => RAW_PRESSURE_DATA::ID,
32262 Self::DATA_STREAM(..) => DATA_STREAM_DATA::ID,
32263 Self::OPEN_DRONE_ID_LOCATION(..) => OPEN_DRONE_ID_LOCATION_DATA::ID,
32264 Self::TUNNEL(..) => TUNNEL_DATA::ID,
32265 Self::NAMED_VALUE_FLOAT(..) => NAMED_VALUE_FLOAT_DATA::ID,
32266 Self::SIM_STATE(..) => SIM_STATE_DATA::ID,
32267 Self::OPEN_DRONE_ID_SYSTEM(..) => OPEN_DRONE_ID_SYSTEM_DATA::ID,
32268 Self::OPEN_DRONE_ID_OPERATOR_ID(..) => OPEN_DRONE_ID_OPERATOR_ID_DATA::ID,
32269 Self::MISSION_WRITE_PARTIAL_LIST(..) => MISSION_WRITE_PARTIAL_LIST_DATA::ID,
32270 Self::DEBUG_FLOAT_ARRAY(..) => DEBUG_FLOAT_ARRAY_DATA::ID,
32271 Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL(..) => {
32272 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::ID
32273 }
32274 Self::PING(..) => PING_DATA::ID,
32275 Self::CAMERA_SETTINGS(..) => CAMERA_SETTINGS_DATA::ID,
32276 Self::TERRAIN_REQUEST(..) => TERRAIN_REQUEST_DATA::ID,
32277 Self::GIMBAL_DEVICE_SET_ATTITUDE(..) => GIMBAL_DEVICE_SET_ATTITUDE_DATA::ID,
32278 Self::ATT_POS_MOCAP(..) => ATT_POS_MOCAP_DATA::ID,
32279 Self::HEARTBEAT(..) => HEARTBEAT_DATA::ID,
32280 Self::OBSTACLE_DISTANCE(..) => OBSTACLE_DISTANCE_DATA::ID,
32281 Self::OPTICAL_FLOW_RAD(..) => OPTICAL_FLOW_RAD_DATA::ID,
32282 Self::HIL_GPS(..) => HIL_GPS_DATA::ID,
32283 Self::WINCH_STATUS(..) => WINCH_STATUS_DATA::ID,
32284 Self::GENERATOR_STATUS(..) => GENERATOR_STATUS_DATA::ID,
32285 Self::FILE_TRANSFER_PROTOCOL(..) => FILE_TRANSFER_PROTOCOL_DATA::ID,
32286 Self::DATA_TRANSMISSION_HANDSHAKE(..) => DATA_TRANSMISSION_HANDSHAKE_DATA::ID,
32287 Self::SUPPORTED_TUNES(..) => SUPPORTED_TUNES_DATA::ID,
32288 Self::SET_GPS_GLOBAL_ORIGIN(..) => SET_GPS_GLOBAL_ORIGIN_DATA::ID,
32289 Self::ATTITUDE_QUATERNION(..) => ATTITUDE_QUATERNION_DATA::ID,
32290 Self::TRAJECTORY_REPRESENTATION_BEZIER(..) => TRAJECTORY_REPRESENTATION_BEZIER_DATA::ID,
32291 Self::FUEL_STATUS(..) => FUEL_STATUS_DATA::ID,
32292 Self::MISSION_CLEAR_ALL(..) => MISSION_CLEAR_ALL_DATA::ID,
32293 Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(..) => {
32294 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::ID
32295 }
32296 Self::LOGGING_DATA_ACKED(..) => LOGGING_DATA_ACKED_DATA::ID,
32297 Self::RESPONSE_EVENT_ERROR(..) => RESPONSE_EVENT_ERROR_DATA::ID,
32298 Self::SCALED_PRESSURE3(..) => SCALED_PRESSURE3_DATA::ID,
32299 Self::CANFD_FRAME(..) => CANFD_FRAME_DATA::ID,
32300 Self::MISSION_REQUEST_INT(..) => MISSION_REQUEST_INT_DATA::ID,
32301 Self::MAG_CAL_REPORT(..) => MAG_CAL_REPORT_DATA::ID,
32302 Self::COMMAND_ACK(..) => COMMAND_ACK_DATA::ID,
32303 Self::MISSION_ITEM_REACHED(..) => MISSION_ITEM_REACHED_DATA::ID,
32304 Self::CHANGE_OPERATOR_CONTROL_ACK(..) => CHANGE_OPERATOR_CONTROL_ACK_DATA::ID,
32305 Self::DEBUG(..) => DEBUG_DATA::ID,
32306 Self::MISSION_COUNT(..) => MISSION_COUNT_DATA::ID,
32307 Self::SERIAL_CONTROL(..) => SERIAL_CONTROL_DATA::ID,
32308 Self::GPS2_RAW(..) => GPS2_RAW_DATA::ID,
32309 Self::FLIGHT_INFORMATION(..) => FLIGHT_INFORMATION_DATA::ID,
32310 Self::GIMBAL_MANAGER_SET_ATTITUDE(..) => GIMBAL_MANAGER_SET_ATTITUDE_DATA::ID,
32311 }
32312 }
32313 fn message_id_from_name(name: &str) -> Option<u32> {
32314 match name {
32315 EVENT_DATA::NAME => Some(EVENT_DATA::ID),
32316 PROTOCOL_VERSION_DATA::NAME => Some(PROTOCOL_VERSION_DATA::ID),
32317 PARAM_VALUE_DATA::NAME => Some(PARAM_VALUE_DATA::ID),
32318 HIL_OPTICAL_FLOW_DATA::NAME => Some(HIL_OPTICAL_FLOW_DATA::ID),
32319 DISTANCE_SENSOR_DATA::NAME => Some(DISTANCE_SENSOR_DATA::ID),
32320 GPS_INPUT_DATA::NAME => Some(GPS_INPUT_DATA::ID),
32321 CAMERA_INFORMATION_DATA::NAME => Some(CAMERA_INFORMATION_DATA::ID),
32322 GIMBAL_DEVICE_INFORMATION_DATA::NAME => Some(GIMBAL_DEVICE_INFORMATION_DATA::ID),
32323 SYSTEM_TIME_DATA::NAME => Some(SYSTEM_TIME_DATA::ID),
32324 SET_HOME_POSITION_DATA::NAME => Some(SET_HOME_POSITION_DATA::ID),
32325 STATUSTEXT_DATA::NAME => Some(STATUSTEXT_DATA::ID),
32326 ATTITUDE_DATA::NAME => Some(ATTITUDE_DATA::ID),
32327 OPEN_DRONE_ID_AUTHENTICATION_DATA::NAME => Some(OPEN_DRONE_ID_AUTHENTICATION_DATA::ID),
32328 HIL_STATE_QUATERNION_DATA::NAME => Some(HIL_STATE_QUATERNION_DATA::ID),
32329 EXTENDED_SYS_STATE_DATA::NAME => Some(EXTENDED_SYS_STATE_DATA::ID),
32330 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::NAME => {
32331 Some(TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::ID)
32332 }
32333 COLLISION_DATA::NAME => Some(COLLISION_DATA::ID),
32334 MISSION_ACK_DATA::NAME => Some(MISSION_ACK_DATA::ID),
32335 SET_POSITION_TARGET_GLOBAL_INT_DATA::NAME => {
32336 Some(SET_POSITION_TARGET_GLOBAL_INT_DATA::ID)
32337 }
32338 ESC_INFO_DATA::NAME => Some(ESC_INFO_DATA::ID),
32339 PLAY_TUNE_V2_DATA::NAME => Some(PLAY_TUNE_V2_DATA::ID),
32340 SERVO_OUTPUT_RAW_DATA::NAME => Some(SERVO_OUTPUT_RAW_DATA::ID),
32341 VICON_POSITION_ESTIMATE_DATA::NAME => Some(VICON_POSITION_ESTIMATE_DATA::ID),
32342 OPEN_DRONE_ID_SELF_ID_DATA::NAME => Some(OPEN_DRONE_ID_SELF_ID_DATA::ID),
32343 RC_CHANNELS_SCALED_DATA::NAME => Some(RC_CHANNELS_SCALED_DATA::ID),
32344 VIDEO_STREAM_STATUS_DATA::NAME => Some(VIDEO_STREAM_STATUS_DATA::ID),
32345 VISION_SPEED_ESTIMATE_DATA::NAME => Some(VISION_SPEED_ESTIMATE_DATA::ID),
32346 WIND_COV_DATA::NAME => Some(WIND_COV_DATA::ID),
32347 SCALED_IMU_DATA::NAME => Some(SCALED_IMU_DATA::ID),
32348 ORBIT_EXECUTION_STATUS_DATA::NAME => Some(ORBIT_EXECUTION_STATUS_DATA::ID),
32349 TERRAIN_REPORT_DATA::NAME => Some(TERRAIN_REPORT_DATA::ID),
32350 BATTERY_STATUS_DATA::NAME => Some(BATTERY_STATUS_DATA::ID),
32351 ESC_STATUS_DATA::NAME => Some(ESC_STATUS_DATA::ID),
32352 SCALED_IMU3_DATA::NAME => Some(SCALED_IMU3_DATA::ID),
32353 ACTUATOR_CONTROL_TARGET_DATA::NAME => Some(ACTUATOR_CONTROL_TARGET_DATA::ID),
32354 GPS_RAW_INT_DATA::NAME => Some(GPS_RAW_INT_DATA::ID),
32355 PARAM_SET_DATA::NAME => Some(PARAM_SET_DATA::ID),
32356 POSITION_TARGET_LOCAL_NED_DATA::NAME => Some(POSITION_TARGET_LOCAL_NED_DATA::ID),
32357 CURRENT_MODE_DATA::NAME => Some(CURRENT_MODE_DATA::ID),
32358 AIS_VESSEL_DATA::NAME => Some(AIS_VESSEL_DATA::ID),
32359 ENCAPSULATED_DATA_DATA::NAME => Some(ENCAPSULATED_DATA_DATA::ID),
32360 ILLUMINATOR_STATUS_DATA::NAME => Some(ILLUMINATOR_STATUS_DATA::ID),
32361 FOLLOW_TARGET_DATA::NAME => Some(FOLLOW_TARGET_DATA::ID),
32362 RC_CHANNELS_RAW_DATA::NAME => Some(RC_CHANNELS_RAW_DATA::ID),
32363 SET_ACTUATOR_CONTROL_TARGET_DATA::NAME => Some(SET_ACTUATOR_CONTROL_TARGET_DATA::ID),
32364 ADSB_VEHICLE_DATA::NAME => Some(ADSB_VEHICLE_DATA::ID),
32365 UAVCAN_NODE_INFO_DATA::NAME => Some(UAVCAN_NODE_INFO_DATA::ID),
32366 UAVCAN_NODE_STATUS_DATA::NAME => Some(UAVCAN_NODE_STATUS_DATA::ID),
32367 GLOBAL_VISION_POSITION_ESTIMATE_DATA::NAME => {
32368 Some(GLOBAL_VISION_POSITION_ESTIMATE_DATA::ID)
32369 }
32370 V2_EXTENSION_DATA::NAME => Some(V2_EXTENSION_DATA::ID),
32371 GPS_RTK_DATA::NAME => Some(GPS_RTK_DATA::ID),
32372 WIFI_CONFIG_AP_DATA::NAME => Some(WIFI_CONFIG_AP_DATA::ID),
32373 COMPONENT_INFORMATION_DATA::NAME => Some(COMPONENT_INFORMATION_DATA::ID),
32374 LOG_REQUEST_DATA_DATA::NAME => Some(LOG_REQUEST_DATA_DATA::ID),
32375 HIL_RC_INPUTS_RAW_DATA::NAME => Some(HIL_RC_INPUTS_RAW_DATA::ID),
32376 ACTUATOR_OUTPUT_STATUS_DATA::NAME => Some(ACTUATOR_OUTPUT_STATUS_DATA::ID),
32377 TIMESYNC_DATA::NAME => Some(TIMESYNC_DATA::ID),
32378 LOGGING_DATA_DATA::NAME => Some(LOGGING_DATA_DATA::ID),
32379 CAN_FILTER_MODIFY_DATA::NAME => Some(CAN_FILTER_MODIFY_DATA::ID),
32380 HYGROMETER_SENSOR_DATA::NAME => Some(HYGROMETER_SENSOR_DATA::ID),
32381 BATTERY_INFO_DATA::NAME => Some(BATTERY_INFO_DATA::ID),
32382 PARAM_EXT_SET_DATA::NAME => Some(PARAM_EXT_SET_DATA::ID),
32383 SAFETY_ALLOWED_AREA_DATA::NAME => Some(SAFETY_ALLOWED_AREA_DATA::ID),
32384 EFI_STATUS_DATA::NAME => Some(EFI_STATUS_DATA::ID),
32385 AUTOPILOT_VERSION_DATA::NAME => Some(AUTOPILOT_VERSION_DATA::ID),
32386 SET_MODE_DATA::NAME => Some(SET_MODE_DATA::ID),
32387 PARAM_MAP_RC_DATA::NAME => Some(PARAM_MAP_RC_DATA::ID),
32388 PARAM_EXT_REQUEST_READ_DATA::NAME => Some(PARAM_EXT_REQUEST_READ_DATA::ID),
32389 SCALED_IMU2_DATA::NAME => Some(SCALED_IMU2_DATA::ID),
32390 PLAY_TUNE_DATA::NAME => Some(PLAY_TUNE_DATA::ID),
32391 PARAM_REQUEST_LIST_DATA::NAME => Some(PARAM_REQUEST_LIST_DATA::ID),
32392 AUTH_KEY_DATA::NAME => Some(AUTH_KEY_DATA::ID),
32393 COMMAND_CANCEL_DATA::NAME => Some(COMMAND_CANCEL_DATA::ID),
32394 MANUAL_CONTROL_DATA::NAME => Some(MANUAL_CONTROL_DATA::ID),
32395 COMMAND_INT_DATA::NAME => Some(COMMAND_INT_DATA::ID),
32396 HIL_CONTROLS_DATA::NAME => Some(HIL_CONTROLS_DATA::ID),
32397 VISION_POSITION_ESTIMATE_DATA::NAME => Some(VISION_POSITION_ESTIMATE_DATA::ID),
32398 GPS_RTCM_DATA_DATA::NAME => Some(GPS_RTCM_DATA_DATA::ID),
32399 MEMORY_VECT_DATA::NAME => Some(MEMORY_VECT_DATA::ID),
32400 BUTTON_CHANGE_DATA::NAME => Some(BUTTON_CHANGE_DATA::ID),
32401 UTM_GLOBAL_POSITION_DATA::NAME => Some(UTM_GLOBAL_POSITION_DATA::ID),
32402 WHEEL_DISTANCE_DATA::NAME => Some(WHEEL_DISTANCE_DATA::ID),
32403 HIGHRES_IMU_DATA::NAME => Some(HIGHRES_IMU_DATA::ID),
32404 CAMERA_TRIGGER_DATA::NAME => Some(CAMERA_TRIGGER_DATA::ID),
32405 GPS_INJECT_DATA_DATA::NAME => Some(GPS_INJECT_DATA_DATA::ID),
32406 CAMERA_THERMAL_RANGE_DATA::NAME => Some(CAMERA_THERMAL_RANGE_DATA::ID),
32407 RAW_RPM_DATA::NAME => Some(RAW_RPM_DATA::ID),
32408 REQUEST_EVENT_DATA::NAME => Some(REQUEST_EVENT_DATA::ID),
32409 LOCAL_POSITION_NED_COV_DATA::NAME => Some(LOCAL_POSITION_NED_COV_DATA::ID),
32410 GLOBAL_POSITION_INT_COV_DATA::NAME => Some(GLOBAL_POSITION_INT_COV_DATA::ID),
32411 LOCAL_POSITION_NED_DATA::NAME => Some(LOCAL_POSITION_NED_DATA::ID),
32412 REQUEST_DATA_STREAM_DATA::NAME => Some(REQUEST_DATA_STREAM_DATA::ID),
32413 TERRAIN_DATA_DATA::NAME => Some(TERRAIN_DATA_DATA::ID),
32414 CAMERA_FOV_STATUS_DATA::NAME => Some(CAMERA_FOV_STATUS_DATA::ID),
32415 TERRAIN_CHECK_DATA::NAME => Some(TERRAIN_CHECK_DATA::ID),
32416 HOME_POSITION_DATA::NAME => Some(HOME_POSITION_DATA::ID),
32417 HIL_SENSOR_DATA::NAME => Some(HIL_SENSOR_DATA::ID),
32418 POWER_STATUS_DATA::NAME => Some(POWER_STATUS_DATA::ID),
32419 HIL_ACTUATOR_CONTROLS_DATA::NAME => Some(HIL_ACTUATOR_CONTROLS_DATA::ID),
32420 GLOBAL_POSITION_INT_DATA::NAME => Some(GLOBAL_POSITION_INT_DATA::ID),
32421 CELLULAR_CONFIG_DATA::NAME => Some(CELLULAR_CONFIG_DATA::ID),
32422 AVAILABLE_MODES_MONITOR_DATA::NAME => Some(AVAILABLE_MODES_MONITOR_DATA::ID),
32423 GPS_STATUS_DATA::NAME => Some(GPS_STATUS_DATA::ID),
32424 SCALED_PRESSURE_DATA::NAME => Some(SCALED_PRESSURE_DATA::ID),
32425 OPTICAL_FLOW_DATA::NAME => Some(OPTICAL_FLOW_DATA::ID),
32426 OPEN_DRONE_ID_ARM_STATUS_DATA::NAME => Some(OPEN_DRONE_ID_ARM_STATUS_DATA::ID),
32427 RC_CHANNELS_OVERRIDE_DATA::NAME => Some(RC_CHANNELS_OVERRIDE_DATA::ID),
32428 LOG_DATA_DATA::NAME => Some(LOG_DATA_DATA::ID),
32429 MISSION_REQUEST_LIST_DATA::NAME => Some(MISSION_REQUEST_LIST_DATA::ID),
32430 ATTITUDE_QUATERNION_COV_DATA::NAME => Some(ATTITUDE_QUATERNION_COV_DATA::ID),
32431 POSITION_TARGET_GLOBAL_INT_DATA::NAME => Some(POSITION_TARGET_GLOBAL_INT_DATA::ID),
32432 GPS2_RTK_DATA::NAME => Some(GPS2_RTK_DATA::ID),
32433 RESOURCE_REQUEST_DATA::NAME => Some(RESOURCE_REQUEST_DATA::ID),
32434 ESTIMATOR_STATUS_DATA::NAME => Some(ESTIMATOR_STATUS_DATA::ID),
32435 ONBOARD_COMPUTER_STATUS_DATA::NAME => Some(ONBOARD_COMPUTER_STATUS_DATA::ID),
32436 LINK_NODE_STATUS_DATA::NAME => Some(LINK_NODE_STATUS_DATA::ID),
32437 CONTROL_SYSTEM_STATE_DATA::NAME => Some(CONTROL_SYSTEM_STATE_DATA::ID),
32438 MESSAGE_INTERVAL_DATA::NAME => Some(MESSAGE_INTERVAL_DATA::ID),
32439 ODOMETRY_DATA::NAME => Some(ODOMETRY_DATA::ID),
32440 VIDEO_STREAM_INFORMATION_DATA::NAME => Some(VIDEO_STREAM_INFORMATION_DATA::ID),
32441 CAMERA_TRACKING_GEO_STATUS_DATA::NAME => Some(CAMERA_TRACKING_GEO_STATUS_DATA::ID),
32442 COMPONENT_METADATA_DATA::NAME => Some(COMPONENT_METADATA_DATA::ID),
32443 RC_CHANNELS_DATA::NAME => Some(RC_CHANNELS_DATA::ID),
32444 ATTITUDE_TARGET_DATA::NAME => Some(ATTITUDE_TARGET_DATA::ID),
32445 CAMERA_TRACKING_IMAGE_STATUS_DATA::NAME => Some(CAMERA_TRACKING_IMAGE_STATUS_DATA::ID),
32446 MISSION_CURRENT_DATA::NAME => Some(MISSION_CURRENT_DATA::ID),
32447 LOG_REQUEST_LIST_DATA::NAME => Some(LOG_REQUEST_LIST_DATA::ID),
32448 ISBD_LINK_STATUS_DATA::NAME => Some(ISBD_LINK_STATUS_DATA::ID),
32449 PARAM_EXT_ACK_DATA::NAME => Some(PARAM_EXT_ACK_DATA::ID),
32450 SETUP_SIGNING_DATA::NAME => Some(SETUP_SIGNING_DATA::ID),
32451 AVAILABLE_MODES_DATA::NAME => Some(AVAILABLE_MODES_DATA::ID),
32452 SAFETY_SET_ALLOWED_AREA_DATA::NAME => Some(SAFETY_SET_ALLOWED_AREA_DATA::ID),
32453 SET_ATTITUDE_TARGET_DATA::NAME => Some(SET_ATTITUDE_TARGET_DATA::ID),
32454 FENCE_STATUS_DATA::NAME => Some(FENCE_STATUS_DATA::ID),
32455 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::NAME => {
32456 Some(LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::ID)
32457 }
32458 SMART_BATTERY_INFO_DATA::NAME => Some(SMART_BATTERY_INFO_DATA::ID),
32459 OPEN_DRONE_ID_MESSAGE_PACK_DATA::NAME => Some(OPEN_DRONE_ID_MESSAGE_PACK_DATA::ID),
32460 TIME_ESTIMATE_TO_TARGET_DATA::NAME => Some(TIME_ESTIMATE_TO_TARGET_DATA::ID),
32461 CAMERA_CAPTURE_STATUS_DATA::NAME => Some(CAMERA_CAPTURE_STATUS_DATA::ID),
32462 ALTITUDE_DATA::NAME => Some(ALTITUDE_DATA::ID),
32463 DEBUG_VECT_DATA::NAME => Some(DEBUG_VECT_DATA::ID),
32464 GIMBAL_MANAGER_SET_PITCHYAW_DATA::NAME => Some(GIMBAL_MANAGER_SET_PITCHYAW_DATA::ID),
32465 CAMERA_IMAGE_CAPTURED_DATA::NAME => Some(CAMERA_IMAGE_CAPTURED_DATA::ID),
32466 COMMAND_LONG_DATA::NAME => Some(COMMAND_LONG_DATA::ID),
32467 PARAM_EXT_REQUEST_LIST_DATA::NAME => Some(PARAM_EXT_REQUEST_LIST_DATA::ID),
32468 PARAM_EXT_VALUE_DATA::NAME => Some(PARAM_EXT_VALUE_DATA::ID),
32469 GIMBAL_MANAGER_INFORMATION_DATA::NAME => Some(GIMBAL_MANAGER_INFORMATION_DATA::ID),
32470 OPEN_DRONE_ID_BASIC_ID_DATA::NAME => Some(OPEN_DRONE_ID_BASIC_ID_DATA::ID),
32471 SCALED_PRESSURE2_DATA::NAME => Some(SCALED_PRESSURE2_DATA::ID),
32472 LANDING_TARGET_DATA::NAME => Some(LANDING_TARGET_DATA::ID),
32473 OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::NAME => Some(OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::ID),
32474 MISSION_REQUEST_PARTIAL_LIST_DATA::NAME => Some(MISSION_REQUEST_PARTIAL_LIST_DATA::ID),
32475 VFR_HUD_DATA::NAME => Some(VFR_HUD_DATA::ID),
32476 SYS_STATUS_DATA::NAME => Some(SYS_STATUS_DATA::ID),
32477 GPS_GLOBAL_ORIGIN_DATA::NAME => Some(GPS_GLOBAL_ORIGIN_DATA::ID),
32478 GIMBAL_MANAGER_STATUS_DATA::NAME => Some(GIMBAL_MANAGER_STATUS_DATA::ID),
32479 LOG_ERASE_DATA::NAME => Some(LOG_ERASE_DATA::ID),
32480 PARAM_REQUEST_READ_DATA::NAME => Some(PARAM_REQUEST_READ_DATA::ID),
32481 HIL_STATE_DATA::NAME => Some(HIL_STATE_DATA::ID),
32482 CURRENT_EVENT_SEQUENCE_DATA::NAME => Some(CURRENT_EVENT_SEQUENCE_DATA::ID),
32483 LOG_ENTRY_DATA::NAME => Some(LOG_ENTRY_DATA::ID),
32484 MISSION_ITEM_INT_DATA::NAME => Some(MISSION_ITEM_INT_DATA::ID),
32485 HIGH_LATENCY2_DATA::NAME => Some(HIGH_LATENCY2_DATA::ID),
32486 CELLULAR_STATUS_DATA::NAME => Some(CELLULAR_STATUS_DATA::ID),
32487 MISSION_ITEM_DATA::NAME => Some(MISSION_ITEM_DATA::ID),
32488 NAV_CONTROLLER_OUTPUT_DATA::NAME => Some(NAV_CONTROLLER_OUTPUT_DATA::ID),
32489 GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::NAME => {
32490 Some(GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::ID)
32491 }
32492 STORAGE_INFORMATION_DATA::NAME => Some(STORAGE_INFORMATION_DATA::ID),
32493 RADIO_STATUS_DATA::NAME => Some(RADIO_STATUS_DATA::ID),
32494 COMPONENT_INFORMATION_BASIC_DATA::NAME => Some(COMPONENT_INFORMATION_BASIC_DATA::ID),
32495 NAMED_VALUE_INT_DATA::NAME => Some(NAMED_VALUE_INT_DATA::ID),
32496 LOG_REQUEST_END_DATA::NAME => Some(LOG_REQUEST_END_DATA::ID),
32497 MISSION_REQUEST_DATA::NAME => Some(MISSION_REQUEST_DATA::ID),
32498 SET_POSITION_TARGET_LOCAL_NED_DATA::NAME => {
32499 Some(SET_POSITION_TARGET_LOCAL_NED_DATA::ID)
32500 }
32501 LOGGING_ACK_DATA::NAME => Some(LOGGING_ACK_DATA::ID),
32502 CAN_FRAME_DATA::NAME => Some(CAN_FRAME_DATA::ID),
32503 HIGH_LATENCY_DATA::NAME => Some(HIGH_LATENCY_DATA::ID),
32504 VIBRATION_DATA::NAME => Some(VIBRATION_DATA::ID),
32505 CHANGE_OPERATOR_CONTROL_DATA::NAME => Some(CHANGE_OPERATOR_CONTROL_DATA::ID),
32506 MANUAL_SETPOINT_DATA::NAME => Some(MANUAL_SETPOINT_DATA::ID),
32507 MOUNT_ORIENTATION_DATA::NAME => Some(MOUNT_ORIENTATION_DATA::ID),
32508 MISSION_SET_CURRENT_DATA::NAME => Some(MISSION_SET_CURRENT_DATA::ID),
32509 RAW_IMU_DATA::NAME => Some(RAW_IMU_DATA::ID),
32510 RAW_PRESSURE_DATA::NAME => Some(RAW_PRESSURE_DATA::ID),
32511 DATA_STREAM_DATA::NAME => Some(DATA_STREAM_DATA::ID),
32512 OPEN_DRONE_ID_LOCATION_DATA::NAME => Some(OPEN_DRONE_ID_LOCATION_DATA::ID),
32513 TUNNEL_DATA::NAME => Some(TUNNEL_DATA::ID),
32514 NAMED_VALUE_FLOAT_DATA::NAME => Some(NAMED_VALUE_FLOAT_DATA::ID),
32515 SIM_STATE_DATA::NAME => Some(SIM_STATE_DATA::ID),
32516 OPEN_DRONE_ID_SYSTEM_DATA::NAME => Some(OPEN_DRONE_ID_SYSTEM_DATA::ID),
32517 OPEN_DRONE_ID_OPERATOR_ID_DATA::NAME => Some(OPEN_DRONE_ID_OPERATOR_ID_DATA::ID),
32518 MISSION_WRITE_PARTIAL_LIST_DATA::NAME => Some(MISSION_WRITE_PARTIAL_LIST_DATA::ID),
32519 DEBUG_FLOAT_ARRAY_DATA::NAME => Some(DEBUG_FLOAT_ARRAY_DATA::ID),
32520 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::NAME => {
32521 Some(GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::ID)
32522 }
32523 PING_DATA::NAME => Some(PING_DATA::ID),
32524 CAMERA_SETTINGS_DATA::NAME => Some(CAMERA_SETTINGS_DATA::ID),
32525 TERRAIN_REQUEST_DATA::NAME => Some(TERRAIN_REQUEST_DATA::ID),
32526 GIMBAL_DEVICE_SET_ATTITUDE_DATA::NAME => Some(GIMBAL_DEVICE_SET_ATTITUDE_DATA::ID),
32527 ATT_POS_MOCAP_DATA::NAME => Some(ATT_POS_MOCAP_DATA::ID),
32528 HEARTBEAT_DATA::NAME => Some(HEARTBEAT_DATA::ID),
32529 OBSTACLE_DISTANCE_DATA::NAME => Some(OBSTACLE_DISTANCE_DATA::ID),
32530 OPTICAL_FLOW_RAD_DATA::NAME => Some(OPTICAL_FLOW_RAD_DATA::ID),
32531 HIL_GPS_DATA::NAME => Some(HIL_GPS_DATA::ID),
32532 WINCH_STATUS_DATA::NAME => Some(WINCH_STATUS_DATA::ID),
32533 GENERATOR_STATUS_DATA::NAME => Some(GENERATOR_STATUS_DATA::ID),
32534 FILE_TRANSFER_PROTOCOL_DATA::NAME => Some(FILE_TRANSFER_PROTOCOL_DATA::ID),
32535 DATA_TRANSMISSION_HANDSHAKE_DATA::NAME => Some(DATA_TRANSMISSION_HANDSHAKE_DATA::ID),
32536 SUPPORTED_TUNES_DATA::NAME => Some(SUPPORTED_TUNES_DATA::ID),
32537 SET_GPS_GLOBAL_ORIGIN_DATA::NAME => Some(SET_GPS_GLOBAL_ORIGIN_DATA::ID),
32538 ATTITUDE_QUATERNION_DATA::NAME => Some(ATTITUDE_QUATERNION_DATA::ID),
32539 TRAJECTORY_REPRESENTATION_BEZIER_DATA::NAME => {
32540 Some(TRAJECTORY_REPRESENTATION_BEZIER_DATA::ID)
32541 }
32542 FUEL_STATUS_DATA::NAME => Some(FUEL_STATUS_DATA::ID),
32543 MISSION_CLEAR_ALL_DATA::NAME => Some(MISSION_CLEAR_ALL_DATA::ID),
32544 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::NAME => {
32545 Some(AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::ID)
32546 }
32547 LOGGING_DATA_ACKED_DATA::NAME => Some(LOGGING_DATA_ACKED_DATA::ID),
32548 RESPONSE_EVENT_ERROR_DATA::NAME => Some(RESPONSE_EVENT_ERROR_DATA::ID),
32549 SCALED_PRESSURE3_DATA::NAME => Some(SCALED_PRESSURE3_DATA::ID),
32550 CANFD_FRAME_DATA::NAME => Some(CANFD_FRAME_DATA::ID),
32551 MISSION_REQUEST_INT_DATA::NAME => Some(MISSION_REQUEST_INT_DATA::ID),
32552 MAG_CAL_REPORT_DATA::NAME => Some(MAG_CAL_REPORT_DATA::ID),
32553 COMMAND_ACK_DATA::NAME => Some(COMMAND_ACK_DATA::ID),
32554 MISSION_ITEM_REACHED_DATA::NAME => Some(MISSION_ITEM_REACHED_DATA::ID),
32555 CHANGE_OPERATOR_CONTROL_ACK_DATA::NAME => Some(CHANGE_OPERATOR_CONTROL_ACK_DATA::ID),
32556 DEBUG_DATA::NAME => Some(DEBUG_DATA::ID),
32557 MISSION_COUNT_DATA::NAME => Some(MISSION_COUNT_DATA::ID),
32558 SERIAL_CONTROL_DATA::NAME => Some(SERIAL_CONTROL_DATA::ID),
32559 GPS2_RAW_DATA::NAME => Some(GPS2_RAW_DATA::ID),
32560 FLIGHT_INFORMATION_DATA::NAME => Some(FLIGHT_INFORMATION_DATA::ID),
32561 GIMBAL_MANAGER_SET_ATTITUDE_DATA::NAME => Some(GIMBAL_MANAGER_SET_ATTITUDE_DATA::ID),
32562 _ => None,
32563 }
32564 }
32565 fn default_message_from_id(id: u32) -> Option<Self> {
32566 match id {
32567 EVENT_DATA::ID => Some(Self::EVENT(EVENT_DATA::default())),
32568 PROTOCOL_VERSION_DATA::ID => {
32569 Some(Self::PROTOCOL_VERSION(PROTOCOL_VERSION_DATA::default()))
32570 }
32571 PARAM_VALUE_DATA::ID => Some(Self::PARAM_VALUE(PARAM_VALUE_DATA::default())),
32572 HIL_OPTICAL_FLOW_DATA::ID => {
32573 Some(Self::HIL_OPTICAL_FLOW(HIL_OPTICAL_FLOW_DATA::default()))
32574 }
32575 DISTANCE_SENSOR_DATA::ID => {
32576 Some(Self::DISTANCE_SENSOR(DISTANCE_SENSOR_DATA::default()))
32577 }
32578 GPS_INPUT_DATA::ID => Some(Self::GPS_INPUT(GPS_INPUT_DATA::default())),
32579 CAMERA_INFORMATION_DATA::ID => {
32580 Some(Self::CAMERA_INFORMATION(CAMERA_INFORMATION_DATA::default()))
32581 }
32582 GIMBAL_DEVICE_INFORMATION_DATA::ID => Some(Self::GIMBAL_DEVICE_INFORMATION(
32583 GIMBAL_DEVICE_INFORMATION_DATA::default(),
32584 )),
32585 SYSTEM_TIME_DATA::ID => Some(Self::SYSTEM_TIME(SYSTEM_TIME_DATA::default())),
32586 SET_HOME_POSITION_DATA::ID => {
32587 Some(Self::SET_HOME_POSITION(SET_HOME_POSITION_DATA::default()))
32588 }
32589 STATUSTEXT_DATA::ID => Some(Self::STATUSTEXT(STATUSTEXT_DATA::default())),
32590 ATTITUDE_DATA::ID => Some(Self::ATTITUDE(ATTITUDE_DATA::default())),
32591 OPEN_DRONE_ID_AUTHENTICATION_DATA::ID => Some(Self::OPEN_DRONE_ID_AUTHENTICATION(
32592 OPEN_DRONE_ID_AUTHENTICATION_DATA::default(),
32593 )),
32594 HIL_STATE_QUATERNION_DATA::ID => Some(Self::HIL_STATE_QUATERNION(
32595 HIL_STATE_QUATERNION_DATA::default(),
32596 )),
32597 EXTENDED_SYS_STATE_DATA::ID => {
32598 Some(Self::EXTENDED_SYS_STATE(EXTENDED_SYS_STATE_DATA::default()))
32599 }
32600 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::ID => {
32601 Some(Self::TRAJECTORY_REPRESENTATION_WAYPOINTS(
32602 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::default(),
32603 ))
32604 }
32605 COLLISION_DATA::ID => Some(Self::COLLISION(COLLISION_DATA::default())),
32606 MISSION_ACK_DATA::ID => Some(Self::MISSION_ACK(MISSION_ACK_DATA::default())),
32607 SET_POSITION_TARGET_GLOBAL_INT_DATA::ID => Some(Self::SET_POSITION_TARGET_GLOBAL_INT(
32608 SET_POSITION_TARGET_GLOBAL_INT_DATA::default(),
32609 )),
32610 ESC_INFO_DATA::ID => Some(Self::ESC_INFO(ESC_INFO_DATA::default())),
32611 PLAY_TUNE_V2_DATA::ID => Some(Self::PLAY_TUNE_V2(PLAY_TUNE_V2_DATA::default())),
32612 SERVO_OUTPUT_RAW_DATA::ID => {
32613 Some(Self::SERVO_OUTPUT_RAW(SERVO_OUTPUT_RAW_DATA::default()))
32614 }
32615 VICON_POSITION_ESTIMATE_DATA::ID => Some(Self::VICON_POSITION_ESTIMATE(
32616 VICON_POSITION_ESTIMATE_DATA::default(),
32617 )),
32618 OPEN_DRONE_ID_SELF_ID_DATA::ID => Some(Self::OPEN_DRONE_ID_SELF_ID(
32619 OPEN_DRONE_ID_SELF_ID_DATA::default(),
32620 )),
32621 RC_CHANNELS_SCALED_DATA::ID => {
32622 Some(Self::RC_CHANNELS_SCALED(RC_CHANNELS_SCALED_DATA::default()))
32623 }
32624 VIDEO_STREAM_STATUS_DATA::ID => Some(Self::VIDEO_STREAM_STATUS(
32625 VIDEO_STREAM_STATUS_DATA::default(),
32626 )),
32627 VISION_SPEED_ESTIMATE_DATA::ID => Some(Self::VISION_SPEED_ESTIMATE(
32628 VISION_SPEED_ESTIMATE_DATA::default(),
32629 )),
32630 WIND_COV_DATA::ID => Some(Self::WIND_COV(WIND_COV_DATA::default())),
32631 SCALED_IMU_DATA::ID => Some(Self::SCALED_IMU(SCALED_IMU_DATA::default())),
32632 ORBIT_EXECUTION_STATUS_DATA::ID => Some(Self::ORBIT_EXECUTION_STATUS(
32633 ORBIT_EXECUTION_STATUS_DATA::default(),
32634 )),
32635 TERRAIN_REPORT_DATA::ID => Some(Self::TERRAIN_REPORT(TERRAIN_REPORT_DATA::default())),
32636 BATTERY_STATUS_DATA::ID => Some(Self::BATTERY_STATUS(BATTERY_STATUS_DATA::default())),
32637 ESC_STATUS_DATA::ID => Some(Self::ESC_STATUS(ESC_STATUS_DATA::default())),
32638 SCALED_IMU3_DATA::ID => Some(Self::SCALED_IMU3(SCALED_IMU3_DATA::default())),
32639 ACTUATOR_CONTROL_TARGET_DATA::ID => Some(Self::ACTUATOR_CONTROL_TARGET(
32640 ACTUATOR_CONTROL_TARGET_DATA::default(),
32641 )),
32642 GPS_RAW_INT_DATA::ID => Some(Self::GPS_RAW_INT(GPS_RAW_INT_DATA::default())),
32643 PARAM_SET_DATA::ID => Some(Self::PARAM_SET(PARAM_SET_DATA::default())),
32644 POSITION_TARGET_LOCAL_NED_DATA::ID => Some(Self::POSITION_TARGET_LOCAL_NED(
32645 POSITION_TARGET_LOCAL_NED_DATA::default(),
32646 )),
32647 CURRENT_MODE_DATA::ID => Some(Self::CURRENT_MODE(CURRENT_MODE_DATA::default())),
32648 AIS_VESSEL_DATA::ID => Some(Self::AIS_VESSEL(AIS_VESSEL_DATA::default())),
32649 ENCAPSULATED_DATA_DATA::ID => {
32650 Some(Self::ENCAPSULATED_DATA(ENCAPSULATED_DATA_DATA::default()))
32651 }
32652 ILLUMINATOR_STATUS_DATA::ID => {
32653 Some(Self::ILLUMINATOR_STATUS(ILLUMINATOR_STATUS_DATA::default()))
32654 }
32655 FOLLOW_TARGET_DATA::ID => Some(Self::FOLLOW_TARGET(FOLLOW_TARGET_DATA::default())),
32656 RC_CHANNELS_RAW_DATA::ID => {
32657 Some(Self::RC_CHANNELS_RAW(RC_CHANNELS_RAW_DATA::default()))
32658 }
32659 SET_ACTUATOR_CONTROL_TARGET_DATA::ID => Some(Self::SET_ACTUATOR_CONTROL_TARGET(
32660 SET_ACTUATOR_CONTROL_TARGET_DATA::default(),
32661 )),
32662 ADSB_VEHICLE_DATA::ID => Some(Self::ADSB_VEHICLE(ADSB_VEHICLE_DATA::default())),
32663 UAVCAN_NODE_INFO_DATA::ID => {
32664 Some(Self::UAVCAN_NODE_INFO(UAVCAN_NODE_INFO_DATA::default()))
32665 }
32666 UAVCAN_NODE_STATUS_DATA::ID => {
32667 Some(Self::UAVCAN_NODE_STATUS(UAVCAN_NODE_STATUS_DATA::default()))
32668 }
32669 GLOBAL_VISION_POSITION_ESTIMATE_DATA::ID => {
32670 Some(Self::GLOBAL_VISION_POSITION_ESTIMATE(
32671 GLOBAL_VISION_POSITION_ESTIMATE_DATA::default(),
32672 ))
32673 }
32674 V2_EXTENSION_DATA::ID => Some(Self::V2_EXTENSION(V2_EXTENSION_DATA::default())),
32675 GPS_RTK_DATA::ID => Some(Self::GPS_RTK(GPS_RTK_DATA::default())),
32676 WIFI_CONFIG_AP_DATA::ID => Some(Self::WIFI_CONFIG_AP(WIFI_CONFIG_AP_DATA::default())),
32677 COMPONENT_INFORMATION_DATA::ID => Some(Self::COMPONENT_INFORMATION(
32678 COMPONENT_INFORMATION_DATA::default(),
32679 )),
32680 LOG_REQUEST_DATA_DATA::ID => {
32681 Some(Self::LOG_REQUEST_DATA(LOG_REQUEST_DATA_DATA::default()))
32682 }
32683 HIL_RC_INPUTS_RAW_DATA::ID => {
32684 Some(Self::HIL_RC_INPUTS_RAW(HIL_RC_INPUTS_RAW_DATA::default()))
32685 }
32686 ACTUATOR_OUTPUT_STATUS_DATA::ID => Some(Self::ACTUATOR_OUTPUT_STATUS(
32687 ACTUATOR_OUTPUT_STATUS_DATA::default(),
32688 )),
32689 TIMESYNC_DATA::ID => Some(Self::TIMESYNC(TIMESYNC_DATA::default())),
32690 LOGGING_DATA_DATA::ID => Some(Self::LOGGING_DATA(LOGGING_DATA_DATA::default())),
32691 CAN_FILTER_MODIFY_DATA::ID => {
32692 Some(Self::CAN_FILTER_MODIFY(CAN_FILTER_MODIFY_DATA::default()))
32693 }
32694 HYGROMETER_SENSOR_DATA::ID => {
32695 Some(Self::HYGROMETER_SENSOR(HYGROMETER_SENSOR_DATA::default()))
32696 }
32697 BATTERY_INFO_DATA::ID => Some(Self::BATTERY_INFO(BATTERY_INFO_DATA::default())),
32698 PARAM_EXT_SET_DATA::ID => Some(Self::PARAM_EXT_SET(PARAM_EXT_SET_DATA::default())),
32699 SAFETY_ALLOWED_AREA_DATA::ID => Some(Self::SAFETY_ALLOWED_AREA(
32700 SAFETY_ALLOWED_AREA_DATA::default(),
32701 )),
32702 EFI_STATUS_DATA::ID => Some(Self::EFI_STATUS(EFI_STATUS_DATA::default())),
32703 AUTOPILOT_VERSION_DATA::ID => {
32704 Some(Self::AUTOPILOT_VERSION(AUTOPILOT_VERSION_DATA::default()))
32705 }
32706 SET_MODE_DATA::ID => Some(Self::SET_MODE(SET_MODE_DATA::default())),
32707 PARAM_MAP_RC_DATA::ID => Some(Self::PARAM_MAP_RC(PARAM_MAP_RC_DATA::default())),
32708 PARAM_EXT_REQUEST_READ_DATA::ID => Some(Self::PARAM_EXT_REQUEST_READ(
32709 PARAM_EXT_REQUEST_READ_DATA::default(),
32710 )),
32711 SCALED_IMU2_DATA::ID => Some(Self::SCALED_IMU2(SCALED_IMU2_DATA::default())),
32712 PLAY_TUNE_DATA::ID => Some(Self::PLAY_TUNE(PLAY_TUNE_DATA::default())),
32713 PARAM_REQUEST_LIST_DATA::ID => {
32714 Some(Self::PARAM_REQUEST_LIST(PARAM_REQUEST_LIST_DATA::default()))
32715 }
32716 AUTH_KEY_DATA::ID => Some(Self::AUTH_KEY(AUTH_KEY_DATA::default())),
32717 COMMAND_CANCEL_DATA::ID => Some(Self::COMMAND_CANCEL(COMMAND_CANCEL_DATA::default())),
32718 MANUAL_CONTROL_DATA::ID => Some(Self::MANUAL_CONTROL(MANUAL_CONTROL_DATA::default())),
32719 COMMAND_INT_DATA::ID => Some(Self::COMMAND_INT(COMMAND_INT_DATA::default())),
32720 HIL_CONTROLS_DATA::ID => Some(Self::HIL_CONTROLS(HIL_CONTROLS_DATA::default())),
32721 VISION_POSITION_ESTIMATE_DATA::ID => Some(Self::VISION_POSITION_ESTIMATE(
32722 VISION_POSITION_ESTIMATE_DATA::default(),
32723 )),
32724 GPS_RTCM_DATA_DATA::ID => Some(Self::GPS_RTCM_DATA(GPS_RTCM_DATA_DATA::default())),
32725 MEMORY_VECT_DATA::ID => Some(Self::MEMORY_VECT(MEMORY_VECT_DATA::default())),
32726 BUTTON_CHANGE_DATA::ID => Some(Self::BUTTON_CHANGE(BUTTON_CHANGE_DATA::default())),
32727 UTM_GLOBAL_POSITION_DATA::ID => Some(Self::UTM_GLOBAL_POSITION(
32728 UTM_GLOBAL_POSITION_DATA::default(),
32729 )),
32730 WHEEL_DISTANCE_DATA::ID => Some(Self::WHEEL_DISTANCE(WHEEL_DISTANCE_DATA::default())),
32731 HIGHRES_IMU_DATA::ID => Some(Self::HIGHRES_IMU(HIGHRES_IMU_DATA::default())),
32732 CAMERA_TRIGGER_DATA::ID => Some(Self::CAMERA_TRIGGER(CAMERA_TRIGGER_DATA::default())),
32733 GPS_INJECT_DATA_DATA::ID => {
32734 Some(Self::GPS_INJECT_DATA(GPS_INJECT_DATA_DATA::default()))
32735 }
32736 CAMERA_THERMAL_RANGE_DATA::ID => Some(Self::CAMERA_THERMAL_RANGE(
32737 CAMERA_THERMAL_RANGE_DATA::default(),
32738 )),
32739 RAW_RPM_DATA::ID => Some(Self::RAW_RPM(RAW_RPM_DATA::default())),
32740 REQUEST_EVENT_DATA::ID => Some(Self::REQUEST_EVENT(REQUEST_EVENT_DATA::default())),
32741 LOCAL_POSITION_NED_COV_DATA::ID => Some(Self::LOCAL_POSITION_NED_COV(
32742 LOCAL_POSITION_NED_COV_DATA::default(),
32743 )),
32744 GLOBAL_POSITION_INT_COV_DATA::ID => Some(Self::GLOBAL_POSITION_INT_COV(
32745 GLOBAL_POSITION_INT_COV_DATA::default(),
32746 )),
32747 LOCAL_POSITION_NED_DATA::ID => {
32748 Some(Self::LOCAL_POSITION_NED(LOCAL_POSITION_NED_DATA::default()))
32749 }
32750 REQUEST_DATA_STREAM_DATA::ID => Some(Self::REQUEST_DATA_STREAM(
32751 REQUEST_DATA_STREAM_DATA::default(),
32752 )),
32753 TERRAIN_DATA_DATA::ID => Some(Self::TERRAIN_DATA(TERRAIN_DATA_DATA::default())),
32754 CAMERA_FOV_STATUS_DATA::ID => {
32755 Some(Self::CAMERA_FOV_STATUS(CAMERA_FOV_STATUS_DATA::default()))
32756 }
32757 TERRAIN_CHECK_DATA::ID => Some(Self::TERRAIN_CHECK(TERRAIN_CHECK_DATA::default())),
32758 HOME_POSITION_DATA::ID => Some(Self::HOME_POSITION(HOME_POSITION_DATA::default())),
32759 HIL_SENSOR_DATA::ID => Some(Self::HIL_SENSOR(HIL_SENSOR_DATA::default())),
32760 POWER_STATUS_DATA::ID => Some(Self::POWER_STATUS(POWER_STATUS_DATA::default())),
32761 HIL_ACTUATOR_CONTROLS_DATA::ID => Some(Self::HIL_ACTUATOR_CONTROLS(
32762 HIL_ACTUATOR_CONTROLS_DATA::default(),
32763 )),
32764 GLOBAL_POSITION_INT_DATA::ID => Some(Self::GLOBAL_POSITION_INT(
32765 GLOBAL_POSITION_INT_DATA::default(),
32766 )),
32767 CELLULAR_CONFIG_DATA::ID => {
32768 Some(Self::CELLULAR_CONFIG(CELLULAR_CONFIG_DATA::default()))
32769 }
32770 AVAILABLE_MODES_MONITOR_DATA::ID => Some(Self::AVAILABLE_MODES_MONITOR(
32771 AVAILABLE_MODES_MONITOR_DATA::default(),
32772 )),
32773 GPS_STATUS_DATA::ID => Some(Self::GPS_STATUS(GPS_STATUS_DATA::default())),
32774 SCALED_PRESSURE_DATA::ID => {
32775 Some(Self::SCALED_PRESSURE(SCALED_PRESSURE_DATA::default()))
32776 }
32777 OPTICAL_FLOW_DATA::ID => Some(Self::OPTICAL_FLOW(OPTICAL_FLOW_DATA::default())),
32778 OPEN_DRONE_ID_ARM_STATUS_DATA::ID => Some(Self::OPEN_DRONE_ID_ARM_STATUS(
32779 OPEN_DRONE_ID_ARM_STATUS_DATA::default(),
32780 )),
32781 RC_CHANNELS_OVERRIDE_DATA::ID => Some(Self::RC_CHANNELS_OVERRIDE(
32782 RC_CHANNELS_OVERRIDE_DATA::default(),
32783 )),
32784 LOG_DATA_DATA::ID => Some(Self::LOG_DATA(LOG_DATA_DATA::default())),
32785 MISSION_REQUEST_LIST_DATA::ID => Some(Self::MISSION_REQUEST_LIST(
32786 MISSION_REQUEST_LIST_DATA::default(),
32787 )),
32788 ATTITUDE_QUATERNION_COV_DATA::ID => Some(Self::ATTITUDE_QUATERNION_COV(
32789 ATTITUDE_QUATERNION_COV_DATA::default(),
32790 )),
32791 POSITION_TARGET_GLOBAL_INT_DATA::ID => Some(Self::POSITION_TARGET_GLOBAL_INT(
32792 POSITION_TARGET_GLOBAL_INT_DATA::default(),
32793 )),
32794 GPS2_RTK_DATA::ID => Some(Self::GPS2_RTK(GPS2_RTK_DATA::default())),
32795 RESOURCE_REQUEST_DATA::ID => {
32796 Some(Self::RESOURCE_REQUEST(RESOURCE_REQUEST_DATA::default()))
32797 }
32798 ESTIMATOR_STATUS_DATA::ID => {
32799 Some(Self::ESTIMATOR_STATUS(ESTIMATOR_STATUS_DATA::default()))
32800 }
32801 ONBOARD_COMPUTER_STATUS_DATA::ID => Some(Self::ONBOARD_COMPUTER_STATUS(
32802 ONBOARD_COMPUTER_STATUS_DATA::default(),
32803 )),
32804 LINK_NODE_STATUS_DATA::ID => {
32805 Some(Self::LINK_NODE_STATUS(LINK_NODE_STATUS_DATA::default()))
32806 }
32807 CONTROL_SYSTEM_STATE_DATA::ID => Some(Self::CONTROL_SYSTEM_STATE(
32808 CONTROL_SYSTEM_STATE_DATA::default(),
32809 )),
32810 MESSAGE_INTERVAL_DATA::ID => {
32811 Some(Self::MESSAGE_INTERVAL(MESSAGE_INTERVAL_DATA::default()))
32812 }
32813 ODOMETRY_DATA::ID => Some(Self::ODOMETRY(ODOMETRY_DATA::default())),
32814 VIDEO_STREAM_INFORMATION_DATA::ID => Some(Self::VIDEO_STREAM_INFORMATION(
32815 VIDEO_STREAM_INFORMATION_DATA::default(),
32816 )),
32817 CAMERA_TRACKING_GEO_STATUS_DATA::ID => Some(Self::CAMERA_TRACKING_GEO_STATUS(
32818 CAMERA_TRACKING_GEO_STATUS_DATA::default(),
32819 )),
32820 COMPONENT_METADATA_DATA::ID => {
32821 Some(Self::COMPONENT_METADATA(COMPONENT_METADATA_DATA::default()))
32822 }
32823 RC_CHANNELS_DATA::ID => Some(Self::RC_CHANNELS(RC_CHANNELS_DATA::default())),
32824 ATTITUDE_TARGET_DATA::ID => {
32825 Some(Self::ATTITUDE_TARGET(ATTITUDE_TARGET_DATA::default()))
32826 }
32827 CAMERA_TRACKING_IMAGE_STATUS_DATA::ID => Some(Self::CAMERA_TRACKING_IMAGE_STATUS(
32828 CAMERA_TRACKING_IMAGE_STATUS_DATA::default(),
32829 )),
32830 MISSION_CURRENT_DATA::ID => {
32831 Some(Self::MISSION_CURRENT(MISSION_CURRENT_DATA::default()))
32832 }
32833 LOG_REQUEST_LIST_DATA::ID => {
32834 Some(Self::LOG_REQUEST_LIST(LOG_REQUEST_LIST_DATA::default()))
32835 }
32836 ISBD_LINK_STATUS_DATA::ID => {
32837 Some(Self::ISBD_LINK_STATUS(ISBD_LINK_STATUS_DATA::default()))
32838 }
32839 PARAM_EXT_ACK_DATA::ID => Some(Self::PARAM_EXT_ACK(PARAM_EXT_ACK_DATA::default())),
32840 SETUP_SIGNING_DATA::ID => Some(Self::SETUP_SIGNING(SETUP_SIGNING_DATA::default())),
32841 AVAILABLE_MODES_DATA::ID => {
32842 Some(Self::AVAILABLE_MODES(AVAILABLE_MODES_DATA::default()))
32843 }
32844 SAFETY_SET_ALLOWED_AREA_DATA::ID => Some(Self::SAFETY_SET_ALLOWED_AREA(
32845 SAFETY_SET_ALLOWED_AREA_DATA::default(),
32846 )),
32847 SET_ATTITUDE_TARGET_DATA::ID => Some(Self::SET_ATTITUDE_TARGET(
32848 SET_ATTITUDE_TARGET_DATA::default(),
32849 )),
32850 FENCE_STATUS_DATA::ID => Some(Self::FENCE_STATUS(FENCE_STATUS_DATA::default())),
32851 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::ID => {
32852 Some(Self::LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET(
32853 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::default(),
32854 ))
32855 }
32856 SMART_BATTERY_INFO_DATA::ID => {
32857 Some(Self::SMART_BATTERY_INFO(SMART_BATTERY_INFO_DATA::default()))
32858 }
32859 OPEN_DRONE_ID_MESSAGE_PACK_DATA::ID => Some(Self::OPEN_DRONE_ID_MESSAGE_PACK(
32860 OPEN_DRONE_ID_MESSAGE_PACK_DATA::default(),
32861 )),
32862 TIME_ESTIMATE_TO_TARGET_DATA::ID => Some(Self::TIME_ESTIMATE_TO_TARGET(
32863 TIME_ESTIMATE_TO_TARGET_DATA::default(),
32864 )),
32865 CAMERA_CAPTURE_STATUS_DATA::ID => Some(Self::CAMERA_CAPTURE_STATUS(
32866 CAMERA_CAPTURE_STATUS_DATA::default(),
32867 )),
32868 ALTITUDE_DATA::ID => Some(Self::ALTITUDE(ALTITUDE_DATA::default())),
32869 DEBUG_VECT_DATA::ID => Some(Self::DEBUG_VECT(DEBUG_VECT_DATA::default())),
32870 GIMBAL_MANAGER_SET_PITCHYAW_DATA::ID => Some(Self::GIMBAL_MANAGER_SET_PITCHYAW(
32871 GIMBAL_MANAGER_SET_PITCHYAW_DATA::default(),
32872 )),
32873 CAMERA_IMAGE_CAPTURED_DATA::ID => Some(Self::CAMERA_IMAGE_CAPTURED(
32874 CAMERA_IMAGE_CAPTURED_DATA::default(),
32875 )),
32876 COMMAND_LONG_DATA::ID => Some(Self::COMMAND_LONG(COMMAND_LONG_DATA::default())),
32877 PARAM_EXT_REQUEST_LIST_DATA::ID => Some(Self::PARAM_EXT_REQUEST_LIST(
32878 PARAM_EXT_REQUEST_LIST_DATA::default(),
32879 )),
32880 PARAM_EXT_VALUE_DATA::ID => {
32881 Some(Self::PARAM_EXT_VALUE(PARAM_EXT_VALUE_DATA::default()))
32882 }
32883 GIMBAL_MANAGER_INFORMATION_DATA::ID => Some(Self::GIMBAL_MANAGER_INFORMATION(
32884 GIMBAL_MANAGER_INFORMATION_DATA::default(),
32885 )),
32886 OPEN_DRONE_ID_BASIC_ID_DATA::ID => Some(Self::OPEN_DRONE_ID_BASIC_ID(
32887 OPEN_DRONE_ID_BASIC_ID_DATA::default(),
32888 )),
32889 SCALED_PRESSURE2_DATA::ID => {
32890 Some(Self::SCALED_PRESSURE2(SCALED_PRESSURE2_DATA::default()))
32891 }
32892 LANDING_TARGET_DATA::ID => Some(Self::LANDING_TARGET(LANDING_TARGET_DATA::default())),
32893 OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::ID => Some(Self::OPEN_DRONE_ID_SYSTEM_UPDATE(
32894 OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::default(),
32895 )),
32896 MISSION_REQUEST_PARTIAL_LIST_DATA::ID => Some(Self::MISSION_REQUEST_PARTIAL_LIST(
32897 MISSION_REQUEST_PARTIAL_LIST_DATA::default(),
32898 )),
32899 VFR_HUD_DATA::ID => Some(Self::VFR_HUD(VFR_HUD_DATA::default())),
32900 SYS_STATUS_DATA::ID => Some(Self::SYS_STATUS(SYS_STATUS_DATA::default())),
32901 GPS_GLOBAL_ORIGIN_DATA::ID => {
32902 Some(Self::GPS_GLOBAL_ORIGIN(GPS_GLOBAL_ORIGIN_DATA::default()))
32903 }
32904 GIMBAL_MANAGER_STATUS_DATA::ID => Some(Self::GIMBAL_MANAGER_STATUS(
32905 GIMBAL_MANAGER_STATUS_DATA::default(),
32906 )),
32907 LOG_ERASE_DATA::ID => Some(Self::LOG_ERASE(LOG_ERASE_DATA::default())),
32908 PARAM_REQUEST_READ_DATA::ID => {
32909 Some(Self::PARAM_REQUEST_READ(PARAM_REQUEST_READ_DATA::default()))
32910 }
32911 HIL_STATE_DATA::ID => Some(Self::HIL_STATE(HIL_STATE_DATA::default())),
32912 CURRENT_EVENT_SEQUENCE_DATA::ID => Some(Self::CURRENT_EVENT_SEQUENCE(
32913 CURRENT_EVENT_SEQUENCE_DATA::default(),
32914 )),
32915 LOG_ENTRY_DATA::ID => Some(Self::LOG_ENTRY(LOG_ENTRY_DATA::default())),
32916 MISSION_ITEM_INT_DATA::ID => {
32917 Some(Self::MISSION_ITEM_INT(MISSION_ITEM_INT_DATA::default()))
32918 }
32919 HIGH_LATENCY2_DATA::ID => Some(Self::HIGH_LATENCY2(HIGH_LATENCY2_DATA::default())),
32920 CELLULAR_STATUS_DATA::ID => {
32921 Some(Self::CELLULAR_STATUS(CELLULAR_STATUS_DATA::default()))
32922 }
32923 MISSION_ITEM_DATA::ID => Some(Self::MISSION_ITEM(MISSION_ITEM_DATA::default())),
32924 NAV_CONTROLLER_OUTPUT_DATA::ID => Some(Self::NAV_CONTROLLER_OUTPUT(
32925 NAV_CONTROLLER_OUTPUT_DATA::default(),
32926 )),
32927 GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::ID => Some(Self::GIMBAL_DEVICE_ATTITUDE_STATUS(
32928 GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::default(),
32929 )),
32930 STORAGE_INFORMATION_DATA::ID => Some(Self::STORAGE_INFORMATION(
32931 STORAGE_INFORMATION_DATA::default(),
32932 )),
32933 RADIO_STATUS_DATA::ID => Some(Self::RADIO_STATUS(RADIO_STATUS_DATA::default())),
32934 COMPONENT_INFORMATION_BASIC_DATA::ID => Some(Self::COMPONENT_INFORMATION_BASIC(
32935 COMPONENT_INFORMATION_BASIC_DATA::default(),
32936 )),
32937 NAMED_VALUE_INT_DATA::ID => {
32938 Some(Self::NAMED_VALUE_INT(NAMED_VALUE_INT_DATA::default()))
32939 }
32940 LOG_REQUEST_END_DATA::ID => {
32941 Some(Self::LOG_REQUEST_END(LOG_REQUEST_END_DATA::default()))
32942 }
32943 MISSION_REQUEST_DATA::ID => {
32944 Some(Self::MISSION_REQUEST(MISSION_REQUEST_DATA::default()))
32945 }
32946 SET_POSITION_TARGET_LOCAL_NED_DATA::ID => Some(Self::SET_POSITION_TARGET_LOCAL_NED(
32947 SET_POSITION_TARGET_LOCAL_NED_DATA::default(),
32948 )),
32949 LOGGING_ACK_DATA::ID => Some(Self::LOGGING_ACK(LOGGING_ACK_DATA::default())),
32950 CAN_FRAME_DATA::ID => Some(Self::CAN_FRAME(CAN_FRAME_DATA::default())),
32951 HIGH_LATENCY_DATA::ID => Some(Self::HIGH_LATENCY(HIGH_LATENCY_DATA::default())),
32952 VIBRATION_DATA::ID => Some(Self::VIBRATION(VIBRATION_DATA::default())),
32953 CHANGE_OPERATOR_CONTROL_DATA::ID => Some(Self::CHANGE_OPERATOR_CONTROL(
32954 CHANGE_OPERATOR_CONTROL_DATA::default(),
32955 )),
32956 MANUAL_SETPOINT_DATA::ID => {
32957 Some(Self::MANUAL_SETPOINT(MANUAL_SETPOINT_DATA::default()))
32958 }
32959 MOUNT_ORIENTATION_DATA::ID => {
32960 Some(Self::MOUNT_ORIENTATION(MOUNT_ORIENTATION_DATA::default()))
32961 }
32962 MISSION_SET_CURRENT_DATA::ID => Some(Self::MISSION_SET_CURRENT(
32963 MISSION_SET_CURRENT_DATA::default(),
32964 )),
32965 RAW_IMU_DATA::ID => Some(Self::RAW_IMU(RAW_IMU_DATA::default())),
32966 RAW_PRESSURE_DATA::ID => Some(Self::RAW_PRESSURE(RAW_PRESSURE_DATA::default())),
32967 DATA_STREAM_DATA::ID => Some(Self::DATA_STREAM(DATA_STREAM_DATA::default())),
32968 OPEN_DRONE_ID_LOCATION_DATA::ID => Some(Self::OPEN_DRONE_ID_LOCATION(
32969 OPEN_DRONE_ID_LOCATION_DATA::default(),
32970 )),
32971 TUNNEL_DATA::ID => Some(Self::TUNNEL(TUNNEL_DATA::default())),
32972 NAMED_VALUE_FLOAT_DATA::ID => {
32973 Some(Self::NAMED_VALUE_FLOAT(NAMED_VALUE_FLOAT_DATA::default()))
32974 }
32975 SIM_STATE_DATA::ID => Some(Self::SIM_STATE(SIM_STATE_DATA::default())),
32976 OPEN_DRONE_ID_SYSTEM_DATA::ID => Some(Self::OPEN_DRONE_ID_SYSTEM(
32977 OPEN_DRONE_ID_SYSTEM_DATA::default(),
32978 )),
32979 OPEN_DRONE_ID_OPERATOR_ID_DATA::ID => Some(Self::OPEN_DRONE_ID_OPERATOR_ID(
32980 OPEN_DRONE_ID_OPERATOR_ID_DATA::default(),
32981 )),
32982 MISSION_WRITE_PARTIAL_LIST_DATA::ID => Some(Self::MISSION_WRITE_PARTIAL_LIST(
32983 MISSION_WRITE_PARTIAL_LIST_DATA::default(),
32984 )),
32985 DEBUG_FLOAT_ARRAY_DATA::ID => {
32986 Some(Self::DEBUG_FLOAT_ARRAY(DEBUG_FLOAT_ARRAY_DATA::default()))
32987 }
32988 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::ID => {
32989 Some(Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL(
32990 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::default(),
32991 ))
32992 }
32993 PING_DATA::ID => Some(Self::PING(PING_DATA::default())),
32994 CAMERA_SETTINGS_DATA::ID => {
32995 Some(Self::CAMERA_SETTINGS(CAMERA_SETTINGS_DATA::default()))
32996 }
32997 TERRAIN_REQUEST_DATA::ID => {
32998 Some(Self::TERRAIN_REQUEST(TERRAIN_REQUEST_DATA::default()))
32999 }
33000 GIMBAL_DEVICE_SET_ATTITUDE_DATA::ID => Some(Self::GIMBAL_DEVICE_SET_ATTITUDE(
33001 GIMBAL_DEVICE_SET_ATTITUDE_DATA::default(),
33002 )),
33003 ATT_POS_MOCAP_DATA::ID => Some(Self::ATT_POS_MOCAP(ATT_POS_MOCAP_DATA::default())),
33004 HEARTBEAT_DATA::ID => Some(Self::HEARTBEAT(HEARTBEAT_DATA::default())),
33005 OBSTACLE_DISTANCE_DATA::ID => {
33006 Some(Self::OBSTACLE_DISTANCE(OBSTACLE_DISTANCE_DATA::default()))
33007 }
33008 OPTICAL_FLOW_RAD_DATA::ID => {
33009 Some(Self::OPTICAL_FLOW_RAD(OPTICAL_FLOW_RAD_DATA::default()))
33010 }
33011 HIL_GPS_DATA::ID => Some(Self::HIL_GPS(HIL_GPS_DATA::default())),
33012 WINCH_STATUS_DATA::ID => Some(Self::WINCH_STATUS(WINCH_STATUS_DATA::default())),
33013 GENERATOR_STATUS_DATA::ID => {
33014 Some(Self::GENERATOR_STATUS(GENERATOR_STATUS_DATA::default()))
33015 }
33016 FILE_TRANSFER_PROTOCOL_DATA::ID => Some(Self::FILE_TRANSFER_PROTOCOL(
33017 FILE_TRANSFER_PROTOCOL_DATA::default(),
33018 )),
33019 DATA_TRANSMISSION_HANDSHAKE_DATA::ID => Some(Self::DATA_TRANSMISSION_HANDSHAKE(
33020 DATA_TRANSMISSION_HANDSHAKE_DATA::default(),
33021 )),
33022 SUPPORTED_TUNES_DATA::ID => {
33023 Some(Self::SUPPORTED_TUNES(SUPPORTED_TUNES_DATA::default()))
33024 }
33025 SET_GPS_GLOBAL_ORIGIN_DATA::ID => Some(Self::SET_GPS_GLOBAL_ORIGIN(
33026 SET_GPS_GLOBAL_ORIGIN_DATA::default(),
33027 )),
33028 ATTITUDE_QUATERNION_DATA::ID => Some(Self::ATTITUDE_QUATERNION(
33029 ATTITUDE_QUATERNION_DATA::default(),
33030 )),
33031 TRAJECTORY_REPRESENTATION_BEZIER_DATA::ID => {
33032 Some(Self::TRAJECTORY_REPRESENTATION_BEZIER(
33033 TRAJECTORY_REPRESENTATION_BEZIER_DATA::default(),
33034 ))
33035 }
33036 FUEL_STATUS_DATA::ID => Some(Self::FUEL_STATUS(FUEL_STATUS_DATA::default())),
33037 MISSION_CLEAR_ALL_DATA::ID => {
33038 Some(Self::MISSION_CLEAR_ALL(MISSION_CLEAR_ALL_DATA::default()))
33039 }
33040 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::ID => {
33041 Some(Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(
33042 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::default(),
33043 ))
33044 }
33045 LOGGING_DATA_ACKED_DATA::ID => {
33046 Some(Self::LOGGING_DATA_ACKED(LOGGING_DATA_ACKED_DATA::default()))
33047 }
33048 RESPONSE_EVENT_ERROR_DATA::ID => Some(Self::RESPONSE_EVENT_ERROR(
33049 RESPONSE_EVENT_ERROR_DATA::default(),
33050 )),
33051 SCALED_PRESSURE3_DATA::ID => {
33052 Some(Self::SCALED_PRESSURE3(SCALED_PRESSURE3_DATA::default()))
33053 }
33054 CANFD_FRAME_DATA::ID => Some(Self::CANFD_FRAME(CANFD_FRAME_DATA::default())),
33055 MISSION_REQUEST_INT_DATA::ID => Some(Self::MISSION_REQUEST_INT(
33056 MISSION_REQUEST_INT_DATA::default(),
33057 )),
33058 MAG_CAL_REPORT_DATA::ID => Some(Self::MAG_CAL_REPORT(MAG_CAL_REPORT_DATA::default())),
33059 COMMAND_ACK_DATA::ID => Some(Self::COMMAND_ACK(COMMAND_ACK_DATA::default())),
33060 MISSION_ITEM_REACHED_DATA::ID => Some(Self::MISSION_ITEM_REACHED(
33061 MISSION_ITEM_REACHED_DATA::default(),
33062 )),
33063 CHANGE_OPERATOR_CONTROL_ACK_DATA::ID => Some(Self::CHANGE_OPERATOR_CONTROL_ACK(
33064 CHANGE_OPERATOR_CONTROL_ACK_DATA::default(),
33065 )),
33066 DEBUG_DATA::ID => Some(Self::DEBUG(DEBUG_DATA::default())),
33067 MISSION_COUNT_DATA::ID => Some(Self::MISSION_COUNT(MISSION_COUNT_DATA::default())),
33068 SERIAL_CONTROL_DATA::ID => Some(Self::SERIAL_CONTROL(SERIAL_CONTROL_DATA::default())),
33069 GPS2_RAW_DATA::ID => Some(Self::GPS2_RAW(GPS2_RAW_DATA::default())),
33070 FLIGHT_INFORMATION_DATA::ID => {
33071 Some(Self::FLIGHT_INFORMATION(FLIGHT_INFORMATION_DATA::default()))
33072 }
33073 GIMBAL_MANAGER_SET_ATTITUDE_DATA::ID => Some(Self::GIMBAL_MANAGER_SET_ATTITUDE(
33074 GIMBAL_MANAGER_SET_ATTITUDE_DATA::default(),
33075 )),
33076 _ => None,
33077 }
33078 }
33079 #[cfg(feature = "arbitrary")]
33080 fn random_message_from_id<R: rand::RngCore>(id: u32, rng: &mut R) -> Option<Self> {
33081 match id {
33082 EVENT_DATA::ID => Some(Self::EVENT(EVENT_DATA::random(rng))),
33083 PROTOCOL_VERSION_DATA::ID => {
33084 Some(Self::PROTOCOL_VERSION(PROTOCOL_VERSION_DATA::random(rng)))
33085 }
33086 PARAM_VALUE_DATA::ID => Some(Self::PARAM_VALUE(PARAM_VALUE_DATA::random(rng))),
33087 HIL_OPTICAL_FLOW_DATA::ID => {
33088 Some(Self::HIL_OPTICAL_FLOW(HIL_OPTICAL_FLOW_DATA::random(rng)))
33089 }
33090 DISTANCE_SENSOR_DATA::ID => {
33091 Some(Self::DISTANCE_SENSOR(DISTANCE_SENSOR_DATA::random(rng)))
33092 }
33093 GPS_INPUT_DATA::ID => Some(Self::GPS_INPUT(GPS_INPUT_DATA::random(rng))),
33094 CAMERA_INFORMATION_DATA::ID => Some(Self::CAMERA_INFORMATION(
33095 CAMERA_INFORMATION_DATA::random(rng),
33096 )),
33097 GIMBAL_DEVICE_INFORMATION_DATA::ID => Some(Self::GIMBAL_DEVICE_INFORMATION(
33098 GIMBAL_DEVICE_INFORMATION_DATA::random(rng),
33099 )),
33100 SYSTEM_TIME_DATA::ID => Some(Self::SYSTEM_TIME(SYSTEM_TIME_DATA::random(rng))),
33101 SET_HOME_POSITION_DATA::ID => {
33102 Some(Self::SET_HOME_POSITION(SET_HOME_POSITION_DATA::random(rng)))
33103 }
33104 STATUSTEXT_DATA::ID => Some(Self::STATUSTEXT(STATUSTEXT_DATA::random(rng))),
33105 ATTITUDE_DATA::ID => Some(Self::ATTITUDE(ATTITUDE_DATA::random(rng))),
33106 OPEN_DRONE_ID_AUTHENTICATION_DATA::ID => Some(Self::OPEN_DRONE_ID_AUTHENTICATION(
33107 OPEN_DRONE_ID_AUTHENTICATION_DATA::random(rng),
33108 )),
33109 HIL_STATE_QUATERNION_DATA::ID => Some(Self::HIL_STATE_QUATERNION(
33110 HIL_STATE_QUATERNION_DATA::random(rng),
33111 )),
33112 EXTENDED_SYS_STATE_DATA::ID => Some(Self::EXTENDED_SYS_STATE(
33113 EXTENDED_SYS_STATE_DATA::random(rng),
33114 )),
33115 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::ID => {
33116 Some(Self::TRAJECTORY_REPRESENTATION_WAYPOINTS(
33117 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::random(rng),
33118 ))
33119 }
33120 COLLISION_DATA::ID => Some(Self::COLLISION(COLLISION_DATA::random(rng))),
33121 MISSION_ACK_DATA::ID => Some(Self::MISSION_ACK(MISSION_ACK_DATA::random(rng))),
33122 SET_POSITION_TARGET_GLOBAL_INT_DATA::ID => Some(Self::SET_POSITION_TARGET_GLOBAL_INT(
33123 SET_POSITION_TARGET_GLOBAL_INT_DATA::random(rng),
33124 )),
33125 ESC_INFO_DATA::ID => Some(Self::ESC_INFO(ESC_INFO_DATA::random(rng))),
33126 PLAY_TUNE_V2_DATA::ID => Some(Self::PLAY_TUNE_V2(PLAY_TUNE_V2_DATA::random(rng))),
33127 SERVO_OUTPUT_RAW_DATA::ID => {
33128 Some(Self::SERVO_OUTPUT_RAW(SERVO_OUTPUT_RAW_DATA::random(rng)))
33129 }
33130 VICON_POSITION_ESTIMATE_DATA::ID => Some(Self::VICON_POSITION_ESTIMATE(
33131 VICON_POSITION_ESTIMATE_DATA::random(rng),
33132 )),
33133 OPEN_DRONE_ID_SELF_ID_DATA::ID => Some(Self::OPEN_DRONE_ID_SELF_ID(
33134 OPEN_DRONE_ID_SELF_ID_DATA::random(rng),
33135 )),
33136 RC_CHANNELS_SCALED_DATA::ID => Some(Self::RC_CHANNELS_SCALED(
33137 RC_CHANNELS_SCALED_DATA::random(rng),
33138 )),
33139 VIDEO_STREAM_STATUS_DATA::ID => Some(Self::VIDEO_STREAM_STATUS(
33140 VIDEO_STREAM_STATUS_DATA::random(rng),
33141 )),
33142 VISION_SPEED_ESTIMATE_DATA::ID => Some(Self::VISION_SPEED_ESTIMATE(
33143 VISION_SPEED_ESTIMATE_DATA::random(rng),
33144 )),
33145 WIND_COV_DATA::ID => Some(Self::WIND_COV(WIND_COV_DATA::random(rng))),
33146 SCALED_IMU_DATA::ID => Some(Self::SCALED_IMU(SCALED_IMU_DATA::random(rng))),
33147 ORBIT_EXECUTION_STATUS_DATA::ID => Some(Self::ORBIT_EXECUTION_STATUS(
33148 ORBIT_EXECUTION_STATUS_DATA::random(rng),
33149 )),
33150 TERRAIN_REPORT_DATA::ID => Some(Self::TERRAIN_REPORT(TERRAIN_REPORT_DATA::random(rng))),
33151 BATTERY_STATUS_DATA::ID => Some(Self::BATTERY_STATUS(BATTERY_STATUS_DATA::random(rng))),
33152 ESC_STATUS_DATA::ID => Some(Self::ESC_STATUS(ESC_STATUS_DATA::random(rng))),
33153 SCALED_IMU3_DATA::ID => Some(Self::SCALED_IMU3(SCALED_IMU3_DATA::random(rng))),
33154 ACTUATOR_CONTROL_TARGET_DATA::ID => Some(Self::ACTUATOR_CONTROL_TARGET(
33155 ACTUATOR_CONTROL_TARGET_DATA::random(rng),
33156 )),
33157 GPS_RAW_INT_DATA::ID => Some(Self::GPS_RAW_INT(GPS_RAW_INT_DATA::random(rng))),
33158 PARAM_SET_DATA::ID => Some(Self::PARAM_SET(PARAM_SET_DATA::random(rng))),
33159 POSITION_TARGET_LOCAL_NED_DATA::ID => Some(Self::POSITION_TARGET_LOCAL_NED(
33160 POSITION_TARGET_LOCAL_NED_DATA::random(rng),
33161 )),
33162 CURRENT_MODE_DATA::ID => Some(Self::CURRENT_MODE(CURRENT_MODE_DATA::random(rng))),
33163 AIS_VESSEL_DATA::ID => Some(Self::AIS_VESSEL(AIS_VESSEL_DATA::random(rng))),
33164 ENCAPSULATED_DATA_DATA::ID => {
33165 Some(Self::ENCAPSULATED_DATA(ENCAPSULATED_DATA_DATA::random(rng)))
33166 }
33167 ILLUMINATOR_STATUS_DATA::ID => Some(Self::ILLUMINATOR_STATUS(
33168 ILLUMINATOR_STATUS_DATA::random(rng),
33169 )),
33170 FOLLOW_TARGET_DATA::ID => Some(Self::FOLLOW_TARGET(FOLLOW_TARGET_DATA::random(rng))),
33171 RC_CHANNELS_RAW_DATA::ID => {
33172 Some(Self::RC_CHANNELS_RAW(RC_CHANNELS_RAW_DATA::random(rng)))
33173 }
33174 SET_ACTUATOR_CONTROL_TARGET_DATA::ID => Some(Self::SET_ACTUATOR_CONTROL_TARGET(
33175 SET_ACTUATOR_CONTROL_TARGET_DATA::random(rng),
33176 )),
33177 ADSB_VEHICLE_DATA::ID => Some(Self::ADSB_VEHICLE(ADSB_VEHICLE_DATA::random(rng))),
33178 UAVCAN_NODE_INFO_DATA::ID => {
33179 Some(Self::UAVCAN_NODE_INFO(UAVCAN_NODE_INFO_DATA::random(rng)))
33180 }
33181 UAVCAN_NODE_STATUS_DATA::ID => Some(Self::UAVCAN_NODE_STATUS(
33182 UAVCAN_NODE_STATUS_DATA::random(rng),
33183 )),
33184 GLOBAL_VISION_POSITION_ESTIMATE_DATA::ID => {
33185 Some(Self::GLOBAL_VISION_POSITION_ESTIMATE(
33186 GLOBAL_VISION_POSITION_ESTIMATE_DATA::random(rng),
33187 ))
33188 }
33189 V2_EXTENSION_DATA::ID => Some(Self::V2_EXTENSION(V2_EXTENSION_DATA::random(rng))),
33190 GPS_RTK_DATA::ID => Some(Self::GPS_RTK(GPS_RTK_DATA::random(rng))),
33191 WIFI_CONFIG_AP_DATA::ID => Some(Self::WIFI_CONFIG_AP(WIFI_CONFIG_AP_DATA::random(rng))),
33192 COMPONENT_INFORMATION_DATA::ID => Some(Self::COMPONENT_INFORMATION(
33193 COMPONENT_INFORMATION_DATA::random(rng),
33194 )),
33195 LOG_REQUEST_DATA_DATA::ID => {
33196 Some(Self::LOG_REQUEST_DATA(LOG_REQUEST_DATA_DATA::random(rng)))
33197 }
33198 HIL_RC_INPUTS_RAW_DATA::ID => {
33199 Some(Self::HIL_RC_INPUTS_RAW(HIL_RC_INPUTS_RAW_DATA::random(rng)))
33200 }
33201 ACTUATOR_OUTPUT_STATUS_DATA::ID => Some(Self::ACTUATOR_OUTPUT_STATUS(
33202 ACTUATOR_OUTPUT_STATUS_DATA::random(rng),
33203 )),
33204 TIMESYNC_DATA::ID => Some(Self::TIMESYNC(TIMESYNC_DATA::random(rng))),
33205 LOGGING_DATA_DATA::ID => Some(Self::LOGGING_DATA(LOGGING_DATA_DATA::random(rng))),
33206 CAN_FILTER_MODIFY_DATA::ID => {
33207 Some(Self::CAN_FILTER_MODIFY(CAN_FILTER_MODIFY_DATA::random(rng)))
33208 }
33209 HYGROMETER_SENSOR_DATA::ID => {
33210 Some(Self::HYGROMETER_SENSOR(HYGROMETER_SENSOR_DATA::random(rng)))
33211 }
33212 BATTERY_INFO_DATA::ID => Some(Self::BATTERY_INFO(BATTERY_INFO_DATA::random(rng))),
33213 PARAM_EXT_SET_DATA::ID => Some(Self::PARAM_EXT_SET(PARAM_EXT_SET_DATA::random(rng))),
33214 SAFETY_ALLOWED_AREA_DATA::ID => Some(Self::SAFETY_ALLOWED_AREA(
33215 SAFETY_ALLOWED_AREA_DATA::random(rng),
33216 )),
33217 EFI_STATUS_DATA::ID => Some(Self::EFI_STATUS(EFI_STATUS_DATA::random(rng))),
33218 AUTOPILOT_VERSION_DATA::ID => {
33219 Some(Self::AUTOPILOT_VERSION(AUTOPILOT_VERSION_DATA::random(rng)))
33220 }
33221 SET_MODE_DATA::ID => Some(Self::SET_MODE(SET_MODE_DATA::random(rng))),
33222 PARAM_MAP_RC_DATA::ID => Some(Self::PARAM_MAP_RC(PARAM_MAP_RC_DATA::random(rng))),
33223 PARAM_EXT_REQUEST_READ_DATA::ID => Some(Self::PARAM_EXT_REQUEST_READ(
33224 PARAM_EXT_REQUEST_READ_DATA::random(rng),
33225 )),
33226 SCALED_IMU2_DATA::ID => Some(Self::SCALED_IMU2(SCALED_IMU2_DATA::random(rng))),
33227 PLAY_TUNE_DATA::ID => Some(Self::PLAY_TUNE(PLAY_TUNE_DATA::random(rng))),
33228 PARAM_REQUEST_LIST_DATA::ID => Some(Self::PARAM_REQUEST_LIST(
33229 PARAM_REQUEST_LIST_DATA::random(rng),
33230 )),
33231 AUTH_KEY_DATA::ID => Some(Self::AUTH_KEY(AUTH_KEY_DATA::random(rng))),
33232 COMMAND_CANCEL_DATA::ID => Some(Self::COMMAND_CANCEL(COMMAND_CANCEL_DATA::random(rng))),
33233 MANUAL_CONTROL_DATA::ID => Some(Self::MANUAL_CONTROL(MANUAL_CONTROL_DATA::random(rng))),
33234 COMMAND_INT_DATA::ID => Some(Self::COMMAND_INT(COMMAND_INT_DATA::random(rng))),
33235 HIL_CONTROLS_DATA::ID => Some(Self::HIL_CONTROLS(HIL_CONTROLS_DATA::random(rng))),
33236 VISION_POSITION_ESTIMATE_DATA::ID => Some(Self::VISION_POSITION_ESTIMATE(
33237 VISION_POSITION_ESTIMATE_DATA::random(rng),
33238 )),
33239 GPS_RTCM_DATA_DATA::ID => Some(Self::GPS_RTCM_DATA(GPS_RTCM_DATA_DATA::random(rng))),
33240 MEMORY_VECT_DATA::ID => Some(Self::MEMORY_VECT(MEMORY_VECT_DATA::random(rng))),
33241 BUTTON_CHANGE_DATA::ID => Some(Self::BUTTON_CHANGE(BUTTON_CHANGE_DATA::random(rng))),
33242 UTM_GLOBAL_POSITION_DATA::ID => Some(Self::UTM_GLOBAL_POSITION(
33243 UTM_GLOBAL_POSITION_DATA::random(rng),
33244 )),
33245 WHEEL_DISTANCE_DATA::ID => Some(Self::WHEEL_DISTANCE(WHEEL_DISTANCE_DATA::random(rng))),
33246 HIGHRES_IMU_DATA::ID => Some(Self::HIGHRES_IMU(HIGHRES_IMU_DATA::random(rng))),
33247 CAMERA_TRIGGER_DATA::ID => Some(Self::CAMERA_TRIGGER(CAMERA_TRIGGER_DATA::random(rng))),
33248 GPS_INJECT_DATA_DATA::ID => {
33249 Some(Self::GPS_INJECT_DATA(GPS_INJECT_DATA_DATA::random(rng)))
33250 }
33251 CAMERA_THERMAL_RANGE_DATA::ID => Some(Self::CAMERA_THERMAL_RANGE(
33252 CAMERA_THERMAL_RANGE_DATA::random(rng),
33253 )),
33254 RAW_RPM_DATA::ID => Some(Self::RAW_RPM(RAW_RPM_DATA::random(rng))),
33255 REQUEST_EVENT_DATA::ID => Some(Self::REQUEST_EVENT(REQUEST_EVENT_DATA::random(rng))),
33256 LOCAL_POSITION_NED_COV_DATA::ID => Some(Self::LOCAL_POSITION_NED_COV(
33257 LOCAL_POSITION_NED_COV_DATA::random(rng),
33258 )),
33259 GLOBAL_POSITION_INT_COV_DATA::ID => Some(Self::GLOBAL_POSITION_INT_COV(
33260 GLOBAL_POSITION_INT_COV_DATA::random(rng),
33261 )),
33262 LOCAL_POSITION_NED_DATA::ID => Some(Self::LOCAL_POSITION_NED(
33263 LOCAL_POSITION_NED_DATA::random(rng),
33264 )),
33265 REQUEST_DATA_STREAM_DATA::ID => Some(Self::REQUEST_DATA_STREAM(
33266 REQUEST_DATA_STREAM_DATA::random(rng),
33267 )),
33268 TERRAIN_DATA_DATA::ID => Some(Self::TERRAIN_DATA(TERRAIN_DATA_DATA::random(rng))),
33269 CAMERA_FOV_STATUS_DATA::ID => {
33270 Some(Self::CAMERA_FOV_STATUS(CAMERA_FOV_STATUS_DATA::random(rng)))
33271 }
33272 TERRAIN_CHECK_DATA::ID => Some(Self::TERRAIN_CHECK(TERRAIN_CHECK_DATA::random(rng))),
33273 HOME_POSITION_DATA::ID => Some(Self::HOME_POSITION(HOME_POSITION_DATA::random(rng))),
33274 HIL_SENSOR_DATA::ID => Some(Self::HIL_SENSOR(HIL_SENSOR_DATA::random(rng))),
33275 POWER_STATUS_DATA::ID => Some(Self::POWER_STATUS(POWER_STATUS_DATA::random(rng))),
33276 HIL_ACTUATOR_CONTROLS_DATA::ID => Some(Self::HIL_ACTUATOR_CONTROLS(
33277 HIL_ACTUATOR_CONTROLS_DATA::random(rng),
33278 )),
33279 GLOBAL_POSITION_INT_DATA::ID => Some(Self::GLOBAL_POSITION_INT(
33280 GLOBAL_POSITION_INT_DATA::random(rng),
33281 )),
33282 CELLULAR_CONFIG_DATA::ID => {
33283 Some(Self::CELLULAR_CONFIG(CELLULAR_CONFIG_DATA::random(rng)))
33284 }
33285 AVAILABLE_MODES_MONITOR_DATA::ID => Some(Self::AVAILABLE_MODES_MONITOR(
33286 AVAILABLE_MODES_MONITOR_DATA::random(rng),
33287 )),
33288 GPS_STATUS_DATA::ID => Some(Self::GPS_STATUS(GPS_STATUS_DATA::random(rng))),
33289 SCALED_PRESSURE_DATA::ID => {
33290 Some(Self::SCALED_PRESSURE(SCALED_PRESSURE_DATA::random(rng)))
33291 }
33292 OPTICAL_FLOW_DATA::ID => Some(Self::OPTICAL_FLOW(OPTICAL_FLOW_DATA::random(rng))),
33293 OPEN_DRONE_ID_ARM_STATUS_DATA::ID => Some(Self::OPEN_DRONE_ID_ARM_STATUS(
33294 OPEN_DRONE_ID_ARM_STATUS_DATA::random(rng),
33295 )),
33296 RC_CHANNELS_OVERRIDE_DATA::ID => Some(Self::RC_CHANNELS_OVERRIDE(
33297 RC_CHANNELS_OVERRIDE_DATA::random(rng),
33298 )),
33299 LOG_DATA_DATA::ID => Some(Self::LOG_DATA(LOG_DATA_DATA::random(rng))),
33300 MISSION_REQUEST_LIST_DATA::ID => Some(Self::MISSION_REQUEST_LIST(
33301 MISSION_REQUEST_LIST_DATA::random(rng),
33302 )),
33303 ATTITUDE_QUATERNION_COV_DATA::ID => Some(Self::ATTITUDE_QUATERNION_COV(
33304 ATTITUDE_QUATERNION_COV_DATA::random(rng),
33305 )),
33306 POSITION_TARGET_GLOBAL_INT_DATA::ID => Some(Self::POSITION_TARGET_GLOBAL_INT(
33307 POSITION_TARGET_GLOBAL_INT_DATA::random(rng),
33308 )),
33309 GPS2_RTK_DATA::ID => Some(Self::GPS2_RTK(GPS2_RTK_DATA::random(rng))),
33310 RESOURCE_REQUEST_DATA::ID => {
33311 Some(Self::RESOURCE_REQUEST(RESOURCE_REQUEST_DATA::random(rng)))
33312 }
33313 ESTIMATOR_STATUS_DATA::ID => {
33314 Some(Self::ESTIMATOR_STATUS(ESTIMATOR_STATUS_DATA::random(rng)))
33315 }
33316 ONBOARD_COMPUTER_STATUS_DATA::ID => Some(Self::ONBOARD_COMPUTER_STATUS(
33317 ONBOARD_COMPUTER_STATUS_DATA::random(rng),
33318 )),
33319 LINK_NODE_STATUS_DATA::ID => {
33320 Some(Self::LINK_NODE_STATUS(LINK_NODE_STATUS_DATA::random(rng)))
33321 }
33322 CONTROL_SYSTEM_STATE_DATA::ID => Some(Self::CONTROL_SYSTEM_STATE(
33323 CONTROL_SYSTEM_STATE_DATA::random(rng),
33324 )),
33325 MESSAGE_INTERVAL_DATA::ID => {
33326 Some(Self::MESSAGE_INTERVAL(MESSAGE_INTERVAL_DATA::random(rng)))
33327 }
33328 ODOMETRY_DATA::ID => Some(Self::ODOMETRY(ODOMETRY_DATA::random(rng))),
33329 VIDEO_STREAM_INFORMATION_DATA::ID => Some(Self::VIDEO_STREAM_INFORMATION(
33330 VIDEO_STREAM_INFORMATION_DATA::random(rng),
33331 )),
33332 CAMERA_TRACKING_GEO_STATUS_DATA::ID => Some(Self::CAMERA_TRACKING_GEO_STATUS(
33333 CAMERA_TRACKING_GEO_STATUS_DATA::random(rng),
33334 )),
33335 COMPONENT_METADATA_DATA::ID => Some(Self::COMPONENT_METADATA(
33336 COMPONENT_METADATA_DATA::random(rng),
33337 )),
33338 RC_CHANNELS_DATA::ID => Some(Self::RC_CHANNELS(RC_CHANNELS_DATA::random(rng))),
33339 ATTITUDE_TARGET_DATA::ID => {
33340 Some(Self::ATTITUDE_TARGET(ATTITUDE_TARGET_DATA::random(rng)))
33341 }
33342 CAMERA_TRACKING_IMAGE_STATUS_DATA::ID => Some(Self::CAMERA_TRACKING_IMAGE_STATUS(
33343 CAMERA_TRACKING_IMAGE_STATUS_DATA::random(rng),
33344 )),
33345 MISSION_CURRENT_DATA::ID => {
33346 Some(Self::MISSION_CURRENT(MISSION_CURRENT_DATA::random(rng)))
33347 }
33348 LOG_REQUEST_LIST_DATA::ID => {
33349 Some(Self::LOG_REQUEST_LIST(LOG_REQUEST_LIST_DATA::random(rng)))
33350 }
33351 ISBD_LINK_STATUS_DATA::ID => {
33352 Some(Self::ISBD_LINK_STATUS(ISBD_LINK_STATUS_DATA::random(rng)))
33353 }
33354 PARAM_EXT_ACK_DATA::ID => Some(Self::PARAM_EXT_ACK(PARAM_EXT_ACK_DATA::random(rng))),
33355 SETUP_SIGNING_DATA::ID => Some(Self::SETUP_SIGNING(SETUP_SIGNING_DATA::random(rng))),
33356 AVAILABLE_MODES_DATA::ID => {
33357 Some(Self::AVAILABLE_MODES(AVAILABLE_MODES_DATA::random(rng)))
33358 }
33359 SAFETY_SET_ALLOWED_AREA_DATA::ID => Some(Self::SAFETY_SET_ALLOWED_AREA(
33360 SAFETY_SET_ALLOWED_AREA_DATA::random(rng),
33361 )),
33362 SET_ATTITUDE_TARGET_DATA::ID => Some(Self::SET_ATTITUDE_TARGET(
33363 SET_ATTITUDE_TARGET_DATA::random(rng),
33364 )),
33365 FENCE_STATUS_DATA::ID => Some(Self::FENCE_STATUS(FENCE_STATUS_DATA::random(rng))),
33366 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::ID => {
33367 Some(Self::LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET(
33368 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::random(rng),
33369 ))
33370 }
33371 SMART_BATTERY_INFO_DATA::ID => Some(Self::SMART_BATTERY_INFO(
33372 SMART_BATTERY_INFO_DATA::random(rng),
33373 )),
33374 OPEN_DRONE_ID_MESSAGE_PACK_DATA::ID => Some(Self::OPEN_DRONE_ID_MESSAGE_PACK(
33375 OPEN_DRONE_ID_MESSAGE_PACK_DATA::random(rng),
33376 )),
33377 TIME_ESTIMATE_TO_TARGET_DATA::ID => Some(Self::TIME_ESTIMATE_TO_TARGET(
33378 TIME_ESTIMATE_TO_TARGET_DATA::random(rng),
33379 )),
33380 CAMERA_CAPTURE_STATUS_DATA::ID => Some(Self::CAMERA_CAPTURE_STATUS(
33381 CAMERA_CAPTURE_STATUS_DATA::random(rng),
33382 )),
33383 ALTITUDE_DATA::ID => Some(Self::ALTITUDE(ALTITUDE_DATA::random(rng))),
33384 DEBUG_VECT_DATA::ID => Some(Self::DEBUG_VECT(DEBUG_VECT_DATA::random(rng))),
33385 GIMBAL_MANAGER_SET_PITCHYAW_DATA::ID => Some(Self::GIMBAL_MANAGER_SET_PITCHYAW(
33386 GIMBAL_MANAGER_SET_PITCHYAW_DATA::random(rng),
33387 )),
33388 CAMERA_IMAGE_CAPTURED_DATA::ID => Some(Self::CAMERA_IMAGE_CAPTURED(
33389 CAMERA_IMAGE_CAPTURED_DATA::random(rng),
33390 )),
33391 COMMAND_LONG_DATA::ID => Some(Self::COMMAND_LONG(COMMAND_LONG_DATA::random(rng))),
33392 PARAM_EXT_REQUEST_LIST_DATA::ID => Some(Self::PARAM_EXT_REQUEST_LIST(
33393 PARAM_EXT_REQUEST_LIST_DATA::random(rng),
33394 )),
33395 PARAM_EXT_VALUE_DATA::ID => {
33396 Some(Self::PARAM_EXT_VALUE(PARAM_EXT_VALUE_DATA::random(rng)))
33397 }
33398 GIMBAL_MANAGER_INFORMATION_DATA::ID => Some(Self::GIMBAL_MANAGER_INFORMATION(
33399 GIMBAL_MANAGER_INFORMATION_DATA::random(rng),
33400 )),
33401 OPEN_DRONE_ID_BASIC_ID_DATA::ID => Some(Self::OPEN_DRONE_ID_BASIC_ID(
33402 OPEN_DRONE_ID_BASIC_ID_DATA::random(rng),
33403 )),
33404 SCALED_PRESSURE2_DATA::ID => {
33405 Some(Self::SCALED_PRESSURE2(SCALED_PRESSURE2_DATA::random(rng)))
33406 }
33407 LANDING_TARGET_DATA::ID => Some(Self::LANDING_TARGET(LANDING_TARGET_DATA::random(rng))),
33408 OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::ID => Some(Self::OPEN_DRONE_ID_SYSTEM_UPDATE(
33409 OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::random(rng),
33410 )),
33411 MISSION_REQUEST_PARTIAL_LIST_DATA::ID => Some(Self::MISSION_REQUEST_PARTIAL_LIST(
33412 MISSION_REQUEST_PARTIAL_LIST_DATA::random(rng),
33413 )),
33414 VFR_HUD_DATA::ID => Some(Self::VFR_HUD(VFR_HUD_DATA::random(rng))),
33415 SYS_STATUS_DATA::ID => Some(Self::SYS_STATUS(SYS_STATUS_DATA::random(rng))),
33416 GPS_GLOBAL_ORIGIN_DATA::ID => {
33417 Some(Self::GPS_GLOBAL_ORIGIN(GPS_GLOBAL_ORIGIN_DATA::random(rng)))
33418 }
33419 GIMBAL_MANAGER_STATUS_DATA::ID => Some(Self::GIMBAL_MANAGER_STATUS(
33420 GIMBAL_MANAGER_STATUS_DATA::random(rng),
33421 )),
33422 LOG_ERASE_DATA::ID => Some(Self::LOG_ERASE(LOG_ERASE_DATA::random(rng))),
33423 PARAM_REQUEST_READ_DATA::ID => Some(Self::PARAM_REQUEST_READ(
33424 PARAM_REQUEST_READ_DATA::random(rng),
33425 )),
33426 HIL_STATE_DATA::ID => Some(Self::HIL_STATE(HIL_STATE_DATA::random(rng))),
33427 CURRENT_EVENT_SEQUENCE_DATA::ID => Some(Self::CURRENT_EVENT_SEQUENCE(
33428 CURRENT_EVENT_SEQUENCE_DATA::random(rng),
33429 )),
33430 LOG_ENTRY_DATA::ID => Some(Self::LOG_ENTRY(LOG_ENTRY_DATA::random(rng))),
33431 MISSION_ITEM_INT_DATA::ID => {
33432 Some(Self::MISSION_ITEM_INT(MISSION_ITEM_INT_DATA::random(rng)))
33433 }
33434 HIGH_LATENCY2_DATA::ID => Some(Self::HIGH_LATENCY2(HIGH_LATENCY2_DATA::random(rng))),
33435 CELLULAR_STATUS_DATA::ID => {
33436 Some(Self::CELLULAR_STATUS(CELLULAR_STATUS_DATA::random(rng)))
33437 }
33438 MISSION_ITEM_DATA::ID => Some(Self::MISSION_ITEM(MISSION_ITEM_DATA::random(rng))),
33439 NAV_CONTROLLER_OUTPUT_DATA::ID => Some(Self::NAV_CONTROLLER_OUTPUT(
33440 NAV_CONTROLLER_OUTPUT_DATA::random(rng),
33441 )),
33442 GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::ID => Some(Self::GIMBAL_DEVICE_ATTITUDE_STATUS(
33443 GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::random(rng),
33444 )),
33445 STORAGE_INFORMATION_DATA::ID => Some(Self::STORAGE_INFORMATION(
33446 STORAGE_INFORMATION_DATA::random(rng),
33447 )),
33448 RADIO_STATUS_DATA::ID => Some(Self::RADIO_STATUS(RADIO_STATUS_DATA::random(rng))),
33449 COMPONENT_INFORMATION_BASIC_DATA::ID => Some(Self::COMPONENT_INFORMATION_BASIC(
33450 COMPONENT_INFORMATION_BASIC_DATA::random(rng),
33451 )),
33452 NAMED_VALUE_INT_DATA::ID => {
33453 Some(Self::NAMED_VALUE_INT(NAMED_VALUE_INT_DATA::random(rng)))
33454 }
33455 LOG_REQUEST_END_DATA::ID => {
33456 Some(Self::LOG_REQUEST_END(LOG_REQUEST_END_DATA::random(rng)))
33457 }
33458 MISSION_REQUEST_DATA::ID => {
33459 Some(Self::MISSION_REQUEST(MISSION_REQUEST_DATA::random(rng)))
33460 }
33461 SET_POSITION_TARGET_LOCAL_NED_DATA::ID => Some(Self::SET_POSITION_TARGET_LOCAL_NED(
33462 SET_POSITION_TARGET_LOCAL_NED_DATA::random(rng),
33463 )),
33464 LOGGING_ACK_DATA::ID => Some(Self::LOGGING_ACK(LOGGING_ACK_DATA::random(rng))),
33465 CAN_FRAME_DATA::ID => Some(Self::CAN_FRAME(CAN_FRAME_DATA::random(rng))),
33466 HIGH_LATENCY_DATA::ID => Some(Self::HIGH_LATENCY(HIGH_LATENCY_DATA::random(rng))),
33467 VIBRATION_DATA::ID => Some(Self::VIBRATION(VIBRATION_DATA::random(rng))),
33468 CHANGE_OPERATOR_CONTROL_DATA::ID => Some(Self::CHANGE_OPERATOR_CONTROL(
33469 CHANGE_OPERATOR_CONTROL_DATA::random(rng),
33470 )),
33471 MANUAL_SETPOINT_DATA::ID => {
33472 Some(Self::MANUAL_SETPOINT(MANUAL_SETPOINT_DATA::random(rng)))
33473 }
33474 MOUNT_ORIENTATION_DATA::ID => {
33475 Some(Self::MOUNT_ORIENTATION(MOUNT_ORIENTATION_DATA::random(rng)))
33476 }
33477 MISSION_SET_CURRENT_DATA::ID => Some(Self::MISSION_SET_CURRENT(
33478 MISSION_SET_CURRENT_DATA::random(rng),
33479 )),
33480 RAW_IMU_DATA::ID => Some(Self::RAW_IMU(RAW_IMU_DATA::random(rng))),
33481 RAW_PRESSURE_DATA::ID => Some(Self::RAW_PRESSURE(RAW_PRESSURE_DATA::random(rng))),
33482 DATA_STREAM_DATA::ID => Some(Self::DATA_STREAM(DATA_STREAM_DATA::random(rng))),
33483 OPEN_DRONE_ID_LOCATION_DATA::ID => Some(Self::OPEN_DRONE_ID_LOCATION(
33484 OPEN_DRONE_ID_LOCATION_DATA::random(rng),
33485 )),
33486 TUNNEL_DATA::ID => Some(Self::TUNNEL(TUNNEL_DATA::random(rng))),
33487 NAMED_VALUE_FLOAT_DATA::ID => {
33488 Some(Self::NAMED_VALUE_FLOAT(NAMED_VALUE_FLOAT_DATA::random(rng)))
33489 }
33490 SIM_STATE_DATA::ID => Some(Self::SIM_STATE(SIM_STATE_DATA::random(rng))),
33491 OPEN_DRONE_ID_SYSTEM_DATA::ID => Some(Self::OPEN_DRONE_ID_SYSTEM(
33492 OPEN_DRONE_ID_SYSTEM_DATA::random(rng),
33493 )),
33494 OPEN_DRONE_ID_OPERATOR_ID_DATA::ID => Some(Self::OPEN_DRONE_ID_OPERATOR_ID(
33495 OPEN_DRONE_ID_OPERATOR_ID_DATA::random(rng),
33496 )),
33497 MISSION_WRITE_PARTIAL_LIST_DATA::ID => Some(Self::MISSION_WRITE_PARTIAL_LIST(
33498 MISSION_WRITE_PARTIAL_LIST_DATA::random(rng),
33499 )),
33500 DEBUG_FLOAT_ARRAY_DATA::ID => {
33501 Some(Self::DEBUG_FLOAT_ARRAY(DEBUG_FLOAT_ARRAY_DATA::random(rng)))
33502 }
33503 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::ID => {
33504 Some(Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL(
33505 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::random(rng),
33506 ))
33507 }
33508 PING_DATA::ID => Some(Self::PING(PING_DATA::random(rng))),
33509 CAMERA_SETTINGS_DATA::ID => {
33510 Some(Self::CAMERA_SETTINGS(CAMERA_SETTINGS_DATA::random(rng)))
33511 }
33512 TERRAIN_REQUEST_DATA::ID => {
33513 Some(Self::TERRAIN_REQUEST(TERRAIN_REQUEST_DATA::random(rng)))
33514 }
33515 GIMBAL_DEVICE_SET_ATTITUDE_DATA::ID => Some(Self::GIMBAL_DEVICE_SET_ATTITUDE(
33516 GIMBAL_DEVICE_SET_ATTITUDE_DATA::random(rng),
33517 )),
33518 ATT_POS_MOCAP_DATA::ID => Some(Self::ATT_POS_MOCAP(ATT_POS_MOCAP_DATA::random(rng))),
33519 HEARTBEAT_DATA::ID => Some(Self::HEARTBEAT(HEARTBEAT_DATA::random(rng))),
33520 OBSTACLE_DISTANCE_DATA::ID => {
33521 Some(Self::OBSTACLE_DISTANCE(OBSTACLE_DISTANCE_DATA::random(rng)))
33522 }
33523 OPTICAL_FLOW_RAD_DATA::ID => {
33524 Some(Self::OPTICAL_FLOW_RAD(OPTICAL_FLOW_RAD_DATA::random(rng)))
33525 }
33526 HIL_GPS_DATA::ID => Some(Self::HIL_GPS(HIL_GPS_DATA::random(rng))),
33527 WINCH_STATUS_DATA::ID => Some(Self::WINCH_STATUS(WINCH_STATUS_DATA::random(rng))),
33528 GENERATOR_STATUS_DATA::ID => {
33529 Some(Self::GENERATOR_STATUS(GENERATOR_STATUS_DATA::random(rng)))
33530 }
33531 FILE_TRANSFER_PROTOCOL_DATA::ID => Some(Self::FILE_TRANSFER_PROTOCOL(
33532 FILE_TRANSFER_PROTOCOL_DATA::random(rng),
33533 )),
33534 DATA_TRANSMISSION_HANDSHAKE_DATA::ID => Some(Self::DATA_TRANSMISSION_HANDSHAKE(
33535 DATA_TRANSMISSION_HANDSHAKE_DATA::random(rng),
33536 )),
33537 SUPPORTED_TUNES_DATA::ID => {
33538 Some(Self::SUPPORTED_TUNES(SUPPORTED_TUNES_DATA::random(rng)))
33539 }
33540 SET_GPS_GLOBAL_ORIGIN_DATA::ID => Some(Self::SET_GPS_GLOBAL_ORIGIN(
33541 SET_GPS_GLOBAL_ORIGIN_DATA::random(rng),
33542 )),
33543 ATTITUDE_QUATERNION_DATA::ID => Some(Self::ATTITUDE_QUATERNION(
33544 ATTITUDE_QUATERNION_DATA::random(rng),
33545 )),
33546 TRAJECTORY_REPRESENTATION_BEZIER_DATA::ID => {
33547 Some(Self::TRAJECTORY_REPRESENTATION_BEZIER(
33548 TRAJECTORY_REPRESENTATION_BEZIER_DATA::random(rng),
33549 ))
33550 }
33551 FUEL_STATUS_DATA::ID => Some(Self::FUEL_STATUS(FUEL_STATUS_DATA::random(rng))),
33552 MISSION_CLEAR_ALL_DATA::ID => {
33553 Some(Self::MISSION_CLEAR_ALL(MISSION_CLEAR_ALL_DATA::random(rng)))
33554 }
33555 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::ID => {
33556 Some(Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(
33557 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::random(rng),
33558 ))
33559 }
33560 LOGGING_DATA_ACKED_DATA::ID => Some(Self::LOGGING_DATA_ACKED(
33561 LOGGING_DATA_ACKED_DATA::random(rng),
33562 )),
33563 RESPONSE_EVENT_ERROR_DATA::ID => Some(Self::RESPONSE_EVENT_ERROR(
33564 RESPONSE_EVENT_ERROR_DATA::random(rng),
33565 )),
33566 SCALED_PRESSURE3_DATA::ID => {
33567 Some(Self::SCALED_PRESSURE3(SCALED_PRESSURE3_DATA::random(rng)))
33568 }
33569 CANFD_FRAME_DATA::ID => Some(Self::CANFD_FRAME(CANFD_FRAME_DATA::random(rng))),
33570 MISSION_REQUEST_INT_DATA::ID => Some(Self::MISSION_REQUEST_INT(
33571 MISSION_REQUEST_INT_DATA::random(rng),
33572 )),
33573 MAG_CAL_REPORT_DATA::ID => Some(Self::MAG_CAL_REPORT(MAG_CAL_REPORT_DATA::random(rng))),
33574 COMMAND_ACK_DATA::ID => Some(Self::COMMAND_ACK(COMMAND_ACK_DATA::random(rng))),
33575 MISSION_ITEM_REACHED_DATA::ID => Some(Self::MISSION_ITEM_REACHED(
33576 MISSION_ITEM_REACHED_DATA::random(rng),
33577 )),
33578 CHANGE_OPERATOR_CONTROL_ACK_DATA::ID => Some(Self::CHANGE_OPERATOR_CONTROL_ACK(
33579 CHANGE_OPERATOR_CONTROL_ACK_DATA::random(rng),
33580 )),
33581 DEBUG_DATA::ID => Some(Self::DEBUG(DEBUG_DATA::random(rng))),
33582 MISSION_COUNT_DATA::ID => Some(Self::MISSION_COUNT(MISSION_COUNT_DATA::random(rng))),
33583 SERIAL_CONTROL_DATA::ID => Some(Self::SERIAL_CONTROL(SERIAL_CONTROL_DATA::random(rng))),
33584 GPS2_RAW_DATA::ID => Some(Self::GPS2_RAW(GPS2_RAW_DATA::random(rng))),
33585 FLIGHT_INFORMATION_DATA::ID => Some(Self::FLIGHT_INFORMATION(
33586 FLIGHT_INFORMATION_DATA::random(rng),
33587 )),
33588 GIMBAL_MANAGER_SET_ATTITUDE_DATA::ID => Some(Self::GIMBAL_MANAGER_SET_ATTITUDE(
33589 GIMBAL_MANAGER_SET_ATTITUDE_DATA::random(rng),
33590 )),
33591 _ => None,
33592 }
33593 }
33594 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
33595 match self {
33596 Self::EVENT(body) => body.ser(version, bytes),
33597 Self::PROTOCOL_VERSION(body) => body.ser(version, bytes),
33598 Self::PARAM_VALUE(body) => body.ser(version, bytes),
33599 Self::HIL_OPTICAL_FLOW(body) => body.ser(version, bytes),
33600 Self::DISTANCE_SENSOR(body) => body.ser(version, bytes),
33601 Self::GPS_INPUT(body) => body.ser(version, bytes),
33602 Self::CAMERA_INFORMATION(body) => body.ser(version, bytes),
33603 Self::GIMBAL_DEVICE_INFORMATION(body) => body.ser(version, bytes),
33604 Self::SYSTEM_TIME(body) => body.ser(version, bytes),
33605 Self::SET_HOME_POSITION(body) => body.ser(version, bytes),
33606 Self::STATUSTEXT(body) => body.ser(version, bytes),
33607 Self::ATTITUDE(body) => body.ser(version, bytes),
33608 Self::OPEN_DRONE_ID_AUTHENTICATION(body) => body.ser(version, bytes),
33609 Self::HIL_STATE_QUATERNION(body) => body.ser(version, bytes),
33610 Self::EXTENDED_SYS_STATE(body) => body.ser(version, bytes),
33611 Self::TRAJECTORY_REPRESENTATION_WAYPOINTS(body) => body.ser(version, bytes),
33612 Self::COLLISION(body) => body.ser(version, bytes),
33613 Self::MISSION_ACK(body) => body.ser(version, bytes),
33614 Self::SET_POSITION_TARGET_GLOBAL_INT(body) => body.ser(version, bytes),
33615 Self::ESC_INFO(body) => body.ser(version, bytes),
33616 Self::PLAY_TUNE_V2(body) => body.ser(version, bytes),
33617 Self::SERVO_OUTPUT_RAW(body) => body.ser(version, bytes),
33618 Self::VICON_POSITION_ESTIMATE(body) => body.ser(version, bytes),
33619 Self::OPEN_DRONE_ID_SELF_ID(body) => body.ser(version, bytes),
33620 Self::RC_CHANNELS_SCALED(body) => body.ser(version, bytes),
33621 Self::VIDEO_STREAM_STATUS(body) => body.ser(version, bytes),
33622 Self::VISION_SPEED_ESTIMATE(body) => body.ser(version, bytes),
33623 Self::WIND_COV(body) => body.ser(version, bytes),
33624 Self::SCALED_IMU(body) => body.ser(version, bytes),
33625 Self::ORBIT_EXECUTION_STATUS(body) => body.ser(version, bytes),
33626 Self::TERRAIN_REPORT(body) => body.ser(version, bytes),
33627 Self::BATTERY_STATUS(body) => body.ser(version, bytes),
33628 Self::ESC_STATUS(body) => body.ser(version, bytes),
33629 Self::SCALED_IMU3(body) => body.ser(version, bytes),
33630 Self::ACTUATOR_CONTROL_TARGET(body) => body.ser(version, bytes),
33631 Self::GPS_RAW_INT(body) => body.ser(version, bytes),
33632 Self::PARAM_SET(body) => body.ser(version, bytes),
33633 Self::POSITION_TARGET_LOCAL_NED(body) => body.ser(version, bytes),
33634 Self::CURRENT_MODE(body) => body.ser(version, bytes),
33635 Self::AIS_VESSEL(body) => body.ser(version, bytes),
33636 Self::ENCAPSULATED_DATA(body) => body.ser(version, bytes),
33637 Self::ILLUMINATOR_STATUS(body) => body.ser(version, bytes),
33638 Self::FOLLOW_TARGET(body) => body.ser(version, bytes),
33639 Self::RC_CHANNELS_RAW(body) => body.ser(version, bytes),
33640 Self::SET_ACTUATOR_CONTROL_TARGET(body) => body.ser(version, bytes),
33641 Self::ADSB_VEHICLE(body) => body.ser(version, bytes),
33642 Self::UAVCAN_NODE_INFO(body) => body.ser(version, bytes),
33643 Self::UAVCAN_NODE_STATUS(body) => body.ser(version, bytes),
33644 Self::GLOBAL_VISION_POSITION_ESTIMATE(body) => body.ser(version, bytes),
33645 Self::V2_EXTENSION(body) => body.ser(version, bytes),
33646 Self::GPS_RTK(body) => body.ser(version, bytes),
33647 Self::WIFI_CONFIG_AP(body) => body.ser(version, bytes),
33648 Self::COMPONENT_INFORMATION(body) => body.ser(version, bytes),
33649 Self::LOG_REQUEST_DATA(body) => body.ser(version, bytes),
33650 Self::HIL_RC_INPUTS_RAW(body) => body.ser(version, bytes),
33651 Self::ACTUATOR_OUTPUT_STATUS(body) => body.ser(version, bytes),
33652 Self::TIMESYNC(body) => body.ser(version, bytes),
33653 Self::LOGGING_DATA(body) => body.ser(version, bytes),
33654 Self::CAN_FILTER_MODIFY(body) => body.ser(version, bytes),
33655 Self::HYGROMETER_SENSOR(body) => body.ser(version, bytes),
33656 Self::BATTERY_INFO(body) => body.ser(version, bytes),
33657 Self::PARAM_EXT_SET(body) => body.ser(version, bytes),
33658 Self::SAFETY_ALLOWED_AREA(body) => body.ser(version, bytes),
33659 Self::EFI_STATUS(body) => body.ser(version, bytes),
33660 Self::AUTOPILOT_VERSION(body) => body.ser(version, bytes),
33661 Self::SET_MODE(body) => body.ser(version, bytes),
33662 Self::PARAM_MAP_RC(body) => body.ser(version, bytes),
33663 Self::PARAM_EXT_REQUEST_READ(body) => body.ser(version, bytes),
33664 Self::SCALED_IMU2(body) => body.ser(version, bytes),
33665 Self::PLAY_TUNE(body) => body.ser(version, bytes),
33666 Self::PARAM_REQUEST_LIST(body) => body.ser(version, bytes),
33667 Self::AUTH_KEY(body) => body.ser(version, bytes),
33668 Self::COMMAND_CANCEL(body) => body.ser(version, bytes),
33669 Self::MANUAL_CONTROL(body) => body.ser(version, bytes),
33670 Self::COMMAND_INT(body) => body.ser(version, bytes),
33671 Self::HIL_CONTROLS(body) => body.ser(version, bytes),
33672 Self::VISION_POSITION_ESTIMATE(body) => body.ser(version, bytes),
33673 Self::GPS_RTCM_DATA(body) => body.ser(version, bytes),
33674 Self::MEMORY_VECT(body) => body.ser(version, bytes),
33675 Self::BUTTON_CHANGE(body) => body.ser(version, bytes),
33676 Self::UTM_GLOBAL_POSITION(body) => body.ser(version, bytes),
33677 Self::WHEEL_DISTANCE(body) => body.ser(version, bytes),
33678 Self::HIGHRES_IMU(body) => body.ser(version, bytes),
33679 Self::CAMERA_TRIGGER(body) => body.ser(version, bytes),
33680 Self::GPS_INJECT_DATA(body) => body.ser(version, bytes),
33681 Self::CAMERA_THERMAL_RANGE(body) => body.ser(version, bytes),
33682 Self::RAW_RPM(body) => body.ser(version, bytes),
33683 Self::REQUEST_EVENT(body) => body.ser(version, bytes),
33684 Self::LOCAL_POSITION_NED_COV(body) => body.ser(version, bytes),
33685 Self::GLOBAL_POSITION_INT_COV(body) => body.ser(version, bytes),
33686 Self::LOCAL_POSITION_NED(body) => body.ser(version, bytes),
33687 Self::REQUEST_DATA_STREAM(body) => body.ser(version, bytes),
33688 Self::TERRAIN_DATA(body) => body.ser(version, bytes),
33689 Self::CAMERA_FOV_STATUS(body) => body.ser(version, bytes),
33690 Self::TERRAIN_CHECK(body) => body.ser(version, bytes),
33691 Self::HOME_POSITION(body) => body.ser(version, bytes),
33692 Self::HIL_SENSOR(body) => body.ser(version, bytes),
33693 Self::POWER_STATUS(body) => body.ser(version, bytes),
33694 Self::HIL_ACTUATOR_CONTROLS(body) => body.ser(version, bytes),
33695 Self::GLOBAL_POSITION_INT(body) => body.ser(version, bytes),
33696 Self::CELLULAR_CONFIG(body) => body.ser(version, bytes),
33697 Self::AVAILABLE_MODES_MONITOR(body) => body.ser(version, bytes),
33698 Self::GPS_STATUS(body) => body.ser(version, bytes),
33699 Self::SCALED_PRESSURE(body) => body.ser(version, bytes),
33700 Self::OPTICAL_FLOW(body) => body.ser(version, bytes),
33701 Self::OPEN_DRONE_ID_ARM_STATUS(body) => body.ser(version, bytes),
33702 Self::RC_CHANNELS_OVERRIDE(body) => body.ser(version, bytes),
33703 Self::LOG_DATA(body) => body.ser(version, bytes),
33704 Self::MISSION_REQUEST_LIST(body) => body.ser(version, bytes),
33705 Self::ATTITUDE_QUATERNION_COV(body) => body.ser(version, bytes),
33706 Self::POSITION_TARGET_GLOBAL_INT(body) => body.ser(version, bytes),
33707 Self::GPS2_RTK(body) => body.ser(version, bytes),
33708 Self::RESOURCE_REQUEST(body) => body.ser(version, bytes),
33709 Self::ESTIMATOR_STATUS(body) => body.ser(version, bytes),
33710 Self::ONBOARD_COMPUTER_STATUS(body) => body.ser(version, bytes),
33711 Self::LINK_NODE_STATUS(body) => body.ser(version, bytes),
33712 Self::CONTROL_SYSTEM_STATE(body) => body.ser(version, bytes),
33713 Self::MESSAGE_INTERVAL(body) => body.ser(version, bytes),
33714 Self::ODOMETRY(body) => body.ser(version, bytes),
33715 Self::VIDEO_STREAM_INFORMATION(body) => body.ser(version, bytes),
33716 Self::CAMERA_TRACKING_GEO_STATUS(body) => body.ser(version, bytes),
33717 Self::COMPONENT_METADATA(body) => body.ser(version, bytes),
33718 Self::RC_CHANNELS(body) => body.ser(version, bytes),
33719 Self::ATTITUDE_TARGET(body) => body.ser(version, bytes),
33720 Self::CAMERA_TRACKING_IMAGE_STATUS(body) => body.ser(version, bytes),
33721 Self::MISSION_CURRENT(body) => body.ser(version, bytes),
33722 Self::LOG_REQUEST_LIST(body) => body.ser(version, bytes),
33723 Self::ISBD_LINK_STATUS(body) => body.ser(version, bytes),
33724 Self::PARAM_EXT_ACK(body) => body.ser(version, bytes),
33725 Self::SETUP_SIGNING(body) => body.ser(version, bytes),
33726 Self::AVAILABLE_MODES(body) => body.ser(version, bytes),
33727 Self::SAFETY_SET_ALLOWED_AREA(body) => body.ser(version, bytes),
33728 Self::SET_ATTITUDE_TARGET(body) => body.ser(version, bytes),
33729 Self::FENCE_STATUS(body) => body.ser(version, bytes),
33730 Self::LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET(body) => body.ser(version, bytes),
33731 Self::SMART_BATTERY_INFO(body) => body.ser(version, bytes),
33732 Self::OPEN_DRONE_ID_MESSAGE_PACK(body) => body.ser(version, bytes),
33733 Self::TIME_ESTIMATE_TO_TARGET(body) => body.ser(version, bytes),
33734 Self::CAMERA_CAPTURE_STATUS(body) => body.ser(version, bytes),
33735 Self::ALTITUDE(body) => body.ser(version, bytes),
33736 Self::DEBUG_VECT(body) => body.ser(version, bytes),
33737 Self::GIMBAL_MANAGER_SET_PITCHYAW(body) => body.ser(version, bytes),
33738 Self::CAMERA_IMAGE_CAPTURED(body) => body.ser(version, bytes),
33739 Self::COMMAND_LONG(body) => body.ser(version, bytes),
33740 Self::PARAM_EXT_REQUEST_LIST(body) => body.ser(version, bytes),
33741 Self::PARAM_EXT_VALUE(body) => body.ser(version, bytes),
33742 Self::GIMBAL_MANAGER_INFORMATION(body) => body.ser(version, bytes),
33743 Self::OPEN_DRONE_ID_BASIC_ID(body) => body.ser(version, bytes),
33744 Self::SCALED_PRESSURE2(body) => body.ser(version, bytes),
33745 Self::LANDING_TARGET(body) => body.ser(version, bytes),
33746 Self::OPEN_DRONE_ID_SYSTEM_UPDATE(body) => body.ser(version, bytes),
33747 Self::MISSION_REQUEST_PARTIAL_LIST(body) => body.ser(version, bytes),
33748 Self::VFR_HUD(body) => body.ser(version, bytes),
33749 Self::SYS_STATUS(body) => body.ser(version, bytes),
33750 Self::GPS_GLOBAL_ORIGIN(body) => body.ser(version, bytes),
33751 Self::GIMBAL_MANAGER_STATUS(body) => body.ser(version, bytes),
33752 Self::LOG_ERASE(body) => body.ser(version, bytes),
33753 Self::PARAM_REQUEST_READ(body) => body.ser(version, bytes),
33754 Self::HIL_STATE(body) => body.ser(version, bytes),
33755 Self::CURRENT_EVENT_SEQUENCE(body) => body.ser(version, bytes),
33756 Self::LOG_ENTRY(body) => body.ser(version, bytes),
33757 Self::MISSION_ITEM_INT(body) => body.ser(version, bytes),
33758 Self::HIGH_LATENCY2(body) => body.ser(version, bytes),
33759 Self::CELLULAR_STATUS(body) => body.ser(version, bytes),
33760 Self::MISSION_ITEM(body) => body.ser(version, bytes),
33761 Self::NAV_CONTROLLER_OUTPUT(body) => body.ser(version, bytes),
33762 Self::GIMBAL_DEVICE_ATTITUDE_STATUS(body) => body.ser(version, bytes),
33763 Self::STORAGE_INFORMATION(body) => body.ser(version, bytes),
33764 Self::RADIO_STATUS(body) => body.ser(version, bytes),
33765 Self::COMPONENT_INFORMATION_BASIC(body) => body.ser(version, bytes),
33766 Self::NAMED_VALUE_INT(body) => body.ser(version, bytes),
33767 Self::LOG_REQUEST_END(body) => body.ser(version, bytes),
33768 Self::MISSION_REQUEST(body) => body.ser(version, bytes),
33769 Self::SET_POSITION_TARGET_LOCAL_NED(body) => body.ser(version, bytes),
33770 Self::LOGGING_ACK(body) => body.ser(version, bytes),
33771 Self::CAN_FRAME(body) => body.ser(version, bytes),
33772 Self::HIGH_LATENCY(body) => body.ser(version, bytes),
33773 Self::VIBRATION(body) => body.ser(version, bytes),
33774 Self::CHANGE_OPERATOR_CONTROL(body) => body.ser(version, bytes),
33775 Self::MANUAL_SETPOINT(body) => body.ser(version, bytes),
33776 Self::MOUNT_ORIENTATION(body) => body.ser(version, bytes),
33777 Self::MISSION_SET_CURRENT(body) => body.ser(version, bytes),
33778 Self::RAW_IMU(body) => body.ser(version, bytes),
33779 Self::RAW_PRESSURE(body) => body.ser(version, bytes),
33780 Self::DATA_STREAM(body) => body.ser(version, bytes),
33781 Self::OPEN_DRONE_ID_LOCATION(body) => body.ser(version, bytes),
33782 Self::TUNNEL(body) => body.ser(version, bytes),
33783 Self::NAMED_VALUE_FLOAT(body) => body.ser(version, bytes),
33784 Self::SIM_STATE(body) => body.ser(version, bytes),
33785 Self::OPEN_DRONE_ID_SYSTEM(body) => body.ser(version, bytes),
33786 Self::OPEN_DRONE_ID_OPERATOR_ID(body) => body.ser(version, bytes),
33787 Self::MISSION_WRITE_PARTIAL_LIST(body) => body.ser(version, bytes),
33788 Self::DEBUG_FLOAT_ARRAY(body) => body.ser(version, bytes),
33789 Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL(body) => body.ser(version, bytes),
33790 Self::PING(body) => body.ser(version, bytes),
33791 Self::CAMERA_SETTINGS(body) => body.ser(version, bytes),
33792 Self::TERRAIN_REQUEST(body) => body.ser(version, bytes),
33793 Self::GIMBAL_DEVICE_SET_ATTITUDE(body) => body.ser(version, bytes),
33794 Self::ATT_POS_MOCAP(body) => body.ser(version, bytes),
33795 Self::HEARTBEAT(body) => body.ser(version, bytes),
33796 Self::OBSTACLE_DISTANCE(body) => body.ser(version, bytes),
33797 Self::OPTICAL_FLOW_RAD(body) => body.ser(version, bytes),
33798 Self::HIL_GPS(body) => body.ser(version, bytes),
33799 Self::WINCH_STATUS(body) => body.ser(version, bytes),
33800 Self::GENERATOR_STATUS(body) => body.ser(version, bytes),
33801 Self::FILE_TRANSFER_PROTOCOL(body) => body.ser(version, bytes),
33802 Self::DATA_TRANSMISSION_HANDSHAKE(body) => body.ser(version, bytes),
33803 Self::SUPPORTED_TUNES(body) => body.ser(version, bytes),
33804 Self::SET_GPS_GLOBAL_ORIGIN(body) => body.ser(version, bytes),
33805 Self::ATTITUDE_QUATERNION(body) => body.ser(version, bytes),
33806 Self::TRAJECTORY_REPRESENTATION_BEZIER(body) => body.ser(version, bytes),
33807 Self::FUEL_STATUS(body) => body.ser(version, bytes),
33808 Self::MISSION_CLEAR_ALL(body) => body.ser(version, bytes),
33809 Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(body) => body.ser(version, bytes),
33810 Self::LOGGING_DATA_ACKED(body) => body.ser(version, bytes),
33811 Self::RESPONSE_EVENT_ERROR(body) => body.ser(version, bytes),
33812 Self::SCALED_PRESSURE3(body) => body.ser(version, bytes),
33813 Self::CANFD_FRAME(body) => body.ser(version, bytes),
33814 Self::MISSION_REQUEST_INT(body) => body.ser(version, bytes),
33815 Self::MAG_CAL_REPORT(body) => body.ser(version, bytes),
33816 Self::COMMAND_ACK(body) => body.ser(version, bytes),
33817 Self::MISSION_ITEM_REACHED(body) => body.ser(version, bytes),
33818 Self::CHANGE_OPERATOR_CONTROL_ACK(body) => body.ser(version, bytes),
33819 Self::DEBUG(body) => body.ser(version, bytes),
33820 Self::MISSION_COUNT(body) => body.ser(version, bytes),
33821 Self::SERIAL_CONTROL(body) => body.ser(version, bytes),
33822 Self::GPS2_RAW(body) => body.ser(version, bytes),
33823 Self::FLIGHT_INFORMATION(body) => body.ser(version, bytes),
33824 Self::GIMBAL_MANAGER_SET_ATTITUDE(body) => body.ser(version, bytes),
33825 }
33826 }
33827 fn extra_crc(id: u32) -> u8 {
33828 match id {
33829 EVENT_DATA::ID => EVENT_DATA::EXTRA_CRC,
33830 PROTOCOL_VERSION_DATA::ID => PROTOCOL_VERSION_DATA::EXTRA_CRC,
33831 PARAM_VALUE_DATA::ID => PARAM_VALUE_DATA::EXTRA_CRC,
33832 HIL_OPTICAL_FLOW_DATA::ID => HIL_OPTICAL_FLOW_DATA::EXTRA_CRC,
33833 DISTANCE_SENSOR_DATA::ID => DISTANCE_SENSOR_DATA::EXTRA_CRC,
33834 GPS_INPUT_DATA::ID => GPS_INPUT_DATA::EXTRA_CRC,
33835 CAMERA_INFORMATION_DATA::ID => CAMERA_INFORMATION_DATA::EXTRA_CRC,
33836 GIMBAL_DEVICE_INFORMATION_DATA::ID => GIMBAL_DEVICE_INFORMATION_DATA::EXTRA_CRC,
33837 SYSTEM_TIME_DATA::ID => SYSTEM_TIME_DATA::EXTRA_CRC,
33838 SET_HOME_POSITION_DATA::ID => SET_HOME_POSITION_DATA::EXTRA_CRC,
33839 STATUSTEXT_DATA::ID => STATUSTEXT_DATA::EXTRA_CRC,
33840 ATTITUDE_DATA::ID => ATTITUDE_DATA::EXTRA_CRC,
33841 OPEN_DRONE_ID_AUTHENTICATION_DATA::ID => OPEN_DRONE_ID_AUTHENTICATION_DATA::EXTRA_CRC,
33842 HIL_STATE_QUATERNION_DATA::ID => HIL_STATE_QUATERNION_DATA::EXTRA_CRC,
33843 EXTENDED_SYS_STATE_DATA::ID => EXTENDED_SYS_STATE_DATA::EXTRA_CRC,
33844 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::ID => {
33845 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::EXTRA_CRC
33846 }
33847 COLLISION_DATA::ID => COLLISION_DATA::EXTRA_CRC,
33848 MISSION_ACK_DATA::ID => MISSION_ACK_DATA::EXTRA_CRC,
33849 SET_POSITION_TARGET_GLOBAL_INT_DATA::ID => {
33850 SET_POSITION_TARGET_GLOBAL_INT_DATA::EXTRA_CRC
33851 }
33852 ESC_INFO_DATA::ID => ESC_INFO_DATA::EXTRA_CRC,
33853 PLAY_TUNE_V2_DATA::ID => PLAY_TUNE_V2_DATA::EXTRA_CRC,
33854 SERVO_OUTPUT_RAW_DATA::ID => SERVO_OUTPUT_RAW_DATA::EXTRA_CRC,
33855 VICON_POSITION_ESTIMATE_DATA::ID => VICON_POSITION_ESTIMATE_DATA::EXTRA_CRC,
33856 OPEN_DRONE_ID_SELF_ID_DATA::ID => OPEN_DRONE_ID_SELF_ID_DATA::EXTRA_CRC,
33857 RC_CHANNELS_SCALED_DATA::ID => RC_CHANNELS_SCALED_DATA::EXTRA_CRC,
33858 VIDEO_STREAM_STATUS_DATA::ID => VIDEO_STREAM_STATUS_DATA::EXTRA_CRC,
33859 VISION_SPEED_ESTIMATE_DATA::ID => VISION_SPEED_ESTIMATE_DATA::EXTRA_CRC,
33860 WIND_COV_DATA::ID => WIND_COV_DATA::EXTRA_CRC,
33861 SCALED_IMU_DATA::ID => SCALED_IMU_DATA::EXTRA_CRC,
33862 ORBIT_EXECUTION_STATUS_DATA::ID => ORBIT_EXECUTION_STATUS_DATA::EXTRA_CRC,
33863 TERRAIN_REPORT_DATA::ID => TERRAIN_REPORT_DATA::EXTRA_CRC,
33864 BATTERY_STATUS_DATA::ID => BATTERY_STATUS_DATA::EXTRA_CRC,
33865 ESC_STATUS_DATA::ID => ESC_STATUS_DATA::EXTRA_CRC,
33866 SCALED_IMU3_DATA::ID => SCALED_IMU3_DATA::EXTRA_CRC,
33867 ACTUATOR_CONTROL_TARGET_DATA::ID => ACTUATOR_CONTROL_TARGET_DATA::EXTRA_CRC,
33868 GPS_RAW_INT_DATA::ID => GPS_RAW_INT_DATA::EXTRA_CRC,
33869 PARAM_SET_DATA::ID => PARAM_SET_DATA::EXTRA_CRC,
33870 POSITION_TARGET_LOCAL_NED_DATA::ID => POSITION_TARGET_LOCAL_NED_DATA::EXTRA_CRC,
33871 CURRENT_MODE_DATA::ID => CURRENT_MODE_DATA::EXTRA_CRC,
33872 AIS_VESSEL_DATA::ID => AIS_VESSEL_DATA::EXTRA_CRC,
33873 ENCAPSULATED_DATA_DATA::ID => ENCAPSULATED_DATA_DATA::EXTRA_CRC,
33874 ILLUMINATOR_STATUS_DATA::ID => ILLUMINATOR_STATUS_DATA::EXTRA_CRC,
33875 FOLLOW_TARGET_DATA::ID => FOLLOW_TARGET_DATA::EXTRA_CRC,
33876 RC_CHANNELS_RAW_DATA::ID => RC_CHANNELS_RAW_DATA::EXTRA_CRC,
33877 SET_ACTUATOR_CONTROL_TARGET_DATA::ID => SET_ACTUATOR_CONTROL_TARGET_DATA::EXTRA_CRC,
33878 ADSB_VEHICLE_DATA::ID => ADSB_VEHICLE_DATA::EXTRA_CRC,
33879 UAVCAN_NODE_INFO_DATA::ID => UAVCAN_NODE_INFO_DATA::EXTRA_CRC,
33880 UAVCAN_NODE_STATUS_DATA::ID => UAVCAN_NODE_STATUS_DATA::EXTRA_CRC,
33881 GLOBAL_VISION_POSITION_ESTIMATE_DATA::ID => {
33882 GLOBAL_VISION_POSITION_ESTIMATE_DATA::EXTRA_CRC
33883 }
33884 V2_EXTENSION_DATA::ID => V2_EXTENSION_DATA::EXTRA_CRC,
33885 GPS_RTK_DATA::ID => GPS_RTK_DATA::EXTRA_CRC,
33886 WIFI_CONFIG_AP_DATA::ID => WIFI_CONFIG_AP_DATA::EXTRA_CRC,
33887 COMPONENT_INFORMATION_DATA::ID => COMPONENT_INFORMATION_DATA::EXTRA_CRC,
33888 LOG_REQUEST_DATA_DATA::ID => LOG_REQUEST_DATA_DATA::EXTRA_CRC,
33889 HIL_RC_INPUTS_RAW_DATA::ID => HIL_RC_INPUTS_RAW_DATA::EXTRA_CRC,
33890 ACTUATOR_OUTPUT_STATUS_DATA::ID => ACTUATOR_OUTPUT_STATUS_DATA::EXTRA_CRC,
33891 TIMESYNC_DATA::ID => TIMESYNC_DATA::EXTRA_CRC,
33892 LOGGING_DATA_DATA::ID => LOGGING_DATA_DATA::EXTRA_CRC,
33893 CAN_FILTER_MODIFY_DATA::ID => CAN_FILTER_MODIFY_DATA::EXTRA_CRC,
33894 HYGROMETER_SENSOR_DATA::ID => HYGROMETER_SENSOR_DATA::EXTRA_CRC,
33895 BATTERY_INFO_DATA::ID => BATTERY_INFO_DATA::EXTRA_CRC,
33896 PARAM_EXT_SET_DATA::ID => PARAM_EXT_SET_DATA::EXTRA_CRC,
33897 SAFETY_ALLOWED_AREA_DATA::ID => SAFETY_ALLOWED_AREA_DATA::EXTRA_CRC,
33898 EFI_STATUS_DATA::ID => EFI_STATUS_DATA::EXTRA_CRC,
33899 AUTOPILOT_VERSION_DATA::ID => AUTOPILOT_VERSION_DATA::EXTRA_CRC,
33900 SET_MODE_DATA::ID => SET_MODE_DATA::EXTRA_CRC,
33901 PARAM_MAP_RC_DATA::ID => PARAM_MAP_RC_DATA::EXTRA_CRC,
33902 PARAM_EXT_REQUEST_READ_DATA::ID => PARAM_EXT_REQUEST_READ_DATA::EXTRA_CRC,
33903 SCALED_IMU2_DATA::ID => SCALED_IMU2_DATA::EXTRA_CRC,
33904 PLAY_TUNE_DATA::ID => PLAY_TUNE_DATA::EXTRA_CRC,
33905 PARAM_REQUEST_LIST_DATA::ID => PARAM_REQUEST_LIST_DATA::EXTRA_CRC,
33906 AUTH_KEY_DATA::ID => AUTH_KEY_DATA::EXTRA_CRC,
33907 COMMAND_CANCEL_DATA::ID => COMMAND_CANCEL_DATA::EXTRA_CRC,
33908 MANUAL_CONTROL_DATA::ID => MANUAL_CONTROL_DATA::EXTRA_CRC,
33909 COMMAND_INT_DATA::ID => COMMAND_INT_DATA::EXTRA_CRC,
33910 HIL_CONTROLS_DATA::ID => HIL_CONTROLS_DATA::EXTRA_CRC,
33911 VISION_POSITION_ESTIMATE_DATA::ID => VISION_POSITION_ESTIMATE_DATA::EXTRA_CRC,
33912 GPS_RTCM_DATA_DATA::ID => GPS_RTCM_DATA_DATA::EXTRA_CRC,
33913 MEMORY_VECT_DATA::ID => MEMORY_VECT_DATA::EXTRA_CRC,
33914 BUTTON_CHANGE_DATA::ID => BUTTON_CHANGE_DATA::EXTRA_CRC,
33915 UTM_GLOBAL_POSITION_DATA::ID => UTM_GLOBAL_POSITION_DATA::EXTRA_CRC,
33916 WHEEL_DISTANCE_DATA::ID => WHEEL_DISTANCE_DATA::EXTRA_CRC,
33917 HIGHRES_IMU_DATA::ID => HIGHRES_IMU_DATA::EXTRA_CRC,
33918 CAMERA_TRIGGER_DATA::ID => CAMERA_TRIGGER_DATA::EXTRA_CRC,
33919 GPS_INJECT_DATA_DATA::ID => GPS_INJECT_DATA_DATA::EXTRA_CRC,
33920 CAMERA_THERMAL_RANGE_DATA::ID => CAMERA_THERMAL_RANGE_DATA::EXTRA_CRC,
33921 RAW_RPM_DATA::ID => RAW_RPM_DATA::EXTRA_CRC,
33922 REQUEST_EVENT_DATA::ID => REQUEST_EVENT_DATA::EXTRA_CRC,
33923 LOCAL_POSITION_NED_COV_DATA::ID => LOCAL_POSITION_NED_COV_DATA::EXTRA_CRC,
33924 GLOBAL_POSITION_INT_COV_DATA::ID => GLOBAL_POSITION_INT_COV_DATA::EXTRA_CRC,
33925 LOCAL_POSITION_NED_DATA::ID => LOCAL_POSITION_NED_DATA::EXTRA_CRC,
33926 REQUEST_DATA_STREAM_DATA::ID => REQUEST_DATA_STREAM_DATA::EXTRA_CRC,
33927 TERRAIN_DATA_DATA::ID => TERRAIN_DATA_DATA::EXTRA_CRC,
33928 CAMERA_FOV_STATUS_DATA::ID => CAMERA_FOV_STATUS_DATA::EXTRA_CRC,
33929 TERRAIN_CHECK_DATA::ID => TERRAIN_CHECK_DATA::EXTRA_CRC,
33930 HOME_POSITION_DATA::ID => HOME_POSITION_DATA::EXTRA_CRC,
33931 HIL_SENSOR_DATA::ID => HIL_SENSOR_DATA::EXTRA_CRC,
33932 POWER_STATUS_DATA::ID => POWER_STATUS_DATA::EXTRA_CRC,
33933 HIL_ACTUATOR_CONTROLS_DATA::ID => HIL_ACTUATOR_CONTROLS_DATA::EXTRA_CRC,
33934 GLOBAL_POSITION_INT_DATA::ID => GLOBAL_POSITION_INT_DATA::EXTRA_CRC,
33935 CELLULAR_CONFIG_DATA::ID => CELLULAR_CONFIG_DATA::EXTRA_CRC,
33936 AVAILABLE_MODES_MONITOR_DATA::ID => AVAILABLE_MODES_MONITOR_DATA::EXTRA_CRC,
33937 GPS_STATUS_DATA::ID => GPS_STATUS_DATA::EXTRA_CRC,
33938 SCALED_PRESSURE_DATA::ID => SCALED_PRESSURE_DATA::EXTRA_CRC,
33939 OPTICAL_FLOW_DATA::ID => OPTICAL_FLOW_DATA::EXTRA_CRC,
33940 OPEN_DRONE_ID_ARM_STATUS_DATA::ID => OPEN_DRONE_ID_ARM_STATUS_DATA::EXTRA_CRC,
33941 RC_CHANNELS_OVERRIDE_DATA::ID => RC_CHANNELS_OVERRIDE_DATA::EXTRA_CRC,
33942 LOG_DATA_DATA::ID => LOG_DATA_DATA::EXTRA_CRC,
33943 MISSION_REQUEST_LIST_DATA::ID => MISSION_REQUEST_LIST_DATA::EXTRA_CRC,
33944 ATTITUDE_QUATERNION_COV_DATA::ID => ATTITUDE_QUATERNION_COV_DATA::EXTRA_CRC,
33945 POSITION_TARGET_GLOBAL_INT_DATA::ID => POSITION_TARGET_GLOBAL_INT_DATA::EXTRA_CRC,
33946 GPS2_RTK_DATA::ID => GPS2_RTK_DATA::EXTRA_CRC,
33947 RESOURCE_REQUEST_DATA::ID => RESOURCE_REQUEST_DATA::EXTRA_CRC,
33948 ESTIMATOR_STATUS_DATA::ID => ESTIMATOR_STATUS_DATA::EXTRA_CRC,
33949 ONBOARD_COMPUTER_STATUS_DATA::ID => ONBOARD_COMPUTER_STATUS_DATA::EXTRA_CRC,
33950 LINK_NODE_STATUS_DATA::ID => LINK_NODE_STATUS_DATA::EXTRA_CRC,
33951 CONTROL_SYSTEM_STATE_DATA::ID => CONTROL_SYSTEM_STATE_DATA::EXTRA_CRC,
33952 MESSAGE_INTERVAL_DATA::ID => MESSAGE_INTERVAL_DATA::EXTRA_CRC,
33953 ODOMETRY_DATA::ID => ODOMETRY_DATA::EXTRA_CRC,
33954 VIDEO_STREAM_INFORMATION_DATA::ID => VIDEO_STREAM_INFORMATION_DATA::EXTRA_CRC,
33955 CAMERA_TRACKING_GEO_STATUS_DATA::ID => CAMERA_TRACKING_GEO_STATUS_DATA::EXTRA_CRC,
33956 COMPONENT_METADATA_DATA::ID => COMPONENT_METADATA_DATA::EXTRA_CRC,
33957 RC_CHANNELS_DATA::ID => RC_CHANNELS_DATA::EXTRA_CRC,
33958 ATTITUDE_TARGET_DATA::ID => ATTITUDE_TARGET_DATA::EXTRA_CRC,
33959 CAMERA_TRACKING_IMAGE_STATUS_DATA::ID => CAMERA_TRACKING_IMAGE_STATUS_DATA::EXTRA_CRC,
33960 MISSION_CURRENT_DATA::ID => MISSION_CURRENT_DATA::EXTRA_CRC,
33961 LOG_REQUEST_LIST_DATA::ID => LOG_REQUEST_LIST_DATA::EXTRA_CRC,
33962 ISBD_LINK_STATUS_DATA::ID => ISBD_LINK_STATUS_DATA::EXTRA_CRC,
33963 PARAM_EXT_ACK_DATA::ID => PARAM_EXT_ACK_DATA::EXTRA_CRC,
33964 SETUP_SIGNING_DATA::ID => SETUP_SIGNING_DATA::EXTRA_CRC,
33965 AVAILABLE_MODES_DATA::ID => AVAILABLE_MODES_DATA::EXTRA_CRC,
33966 SAFETY_SET_ALLOWED_AREA_DATA::ID => SAFETY_SET_ALLOWED_AREA_DATA::EXTRA_CRC,
33967 SET_ATTITUDE_TARGET_DATA::ID => SET_ATTITUDE_TARGET_DATA::EXTRA_CRC,
33968 FENCE_STATUS_DATA::ID => FENCE_STATUS_DATA::EXTRA_CRC,
33969 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::ID => {
33970 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::EXTRA_CRC
33971 }
33972 SMART_BATTERY_INFO_DATA::ID => SMART_BATTERY_INFO_DATA::EXTRA_CRC,
33973 OPEN_DRONE_ID_MESSAGE_PACK_DATA::ID => OPEN_DRONE_ID_MESSAGE_PACK_DATA::EXTRA_CRC,
33974 TIME_ESTIMATE_TO_TARGET_DATA::ID => TIME_ESTIMATE_TO_TARGET_DATA::EXTRA_CRC,
33975 CAMERA_CAPTURE_STATUS_DATA::ID => CAMERA_CAPTURE_STATUS_DATA::EXTRA_CRC,
33976 ALTITUDE_DATA::ID => ALTITUDE_DATA::EXTRA_CRC,
33977 DEBUG_VECT_DATA::ID => DEBUG_VECT_DATA::EXTRA_CRC,
33978 GIMBAL_MANAGER_SET_PITCHYAW_DATA::ID => GIMBAL_MANAGER_SET_PITCHYAW_DATA::EXTRA_CRC,
33979 CAMERA_IMAGE_CAPTURED_DATA::ID => CAMERA_IMAGE_CAPTURED_DATA::EXTRA_CRC,
33980 COMMAND_LONG_DATA::ID => COMMAND_LONG_DATA::EXTRA_CRC,
33981 PARAM_EXT_REQUEST_LIST_DATA::ID => PARAM_EXT_REQUEST_LIST_DATA::EXTRA_CRC,
33982 PARAM_EXT_VALUE_DATA::ID => PARAM_EXT_VALUE_DATA::EXTRA_CRC,
33983 GIMBAL_MANAGER_INFORMATION_DATA::ID => GIMBAL_MANAGER_INFORMATION_DATA::EXTRA_CRC,
33984 OPEN_DRONE_ID_BASIC_ID_DATA::ID => OPEN_DRONE_ID_BASIC_ID_DATA::EXTRA_CRC,
33985 SCALED_PRESSURE2_DATA::ID => SCALED_PRESSURE2_DATA::EXTRA_CRC,
33986 LANDING_TARGET_DATA::ID => LANDING_TARGET_DATA::EXTRA_CRC,
33987 OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::ID => OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::EXTRA_CRC,
33988 MISSION_REQUEST_PARTIAL_LIST_DATA::ID => MISSION_REQUEST_PARTIAL_LIST_DATA::EXTRA_CRC,
33989 VFR_HUD_DATA::ID => VFR_HUD_DATA::EXTRA_CRC,
33990 SYS_STATUS_DATA::ID => SYS_STATUS_DATA::EXTRA_CRC,
33991 GPS_GLOBAL_ORIGIN_DATA::ID => GPS_GLOBAL_ORIGIN_DATA::EXTRA_CRC,
33992 GIMBAL_MANAGER_STATUS_DATA::ID => GIMBAL_MANAGER_STATUS_DATA::EXTRA_CRC,
33993 LOG_ERASE_DATA::ID => LOG_ERASE_DATA::EXTRA_CRC,
33994 PARAM_REQUEST_READ_DATA::ID => PARAM_REQUEST_READ_DATA::EXTRA_CRC,
33995 HIL_STATE_DATA::ID => HIL_STATE_DATA::EXTRA_CRC,
33996 CURRENT_EVENT_SEQUENCE_DATA::ID => CURRENT_EVENT_SEQUENCE_DATA::EXTRA_CRC,
33997 LOG_ENTRY_DATA::ID => LOG_ENTRY_DATA::EXTRA_CRC,
33998 MISSION_ITEM_INT_DATA::ID => MISSION_ITEM_INT_DATA::EXTRA_CRC,
33999 HIGH_LATENCY2_DATA::ID => HIGH_LATENCY2_DATA::EXTRA_CRC,
34000 CELLULAR_STATUS_DATA::ID => CELLULAR_STATUS_DATA::EXTRA_CRC,
34001 MISSION_ITEM_DATA::ID => MISSION_ITEM_DATA::EXTRA_CRC,
34002 NAV_CONTROLLER_OUTPUT_DATA::ID => NAV_CONTROLLER_OUTPUT_DATA::EXTRA_CRC,
34003 GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::ID => GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::EXTRA_CRC,
34004 STORAGE_INFORMATION_DATA::ID => STORAGE_INFORMATION_DATA::EXTRA_CRC,
34005 RADIO_STATUS_DATA::ID => RADIO_STATUS_DATA::EXTRA_CRC,
34006 COMPONENT_INFORMATION_BASIC_DATA::ID => COMPONENT_INFORMATION_BASIC_DATA::EXTRA_CRC,
34007 NAMED_VALUE_INT_DATA::ID => NAMED_VALUE_INT_DATA::EXTRA_CRC,
34008 LOG_REQUEST_END_DATA::ID => LOG_REQUEST_END_DATA::EXTRA_CRC,
34009 MISSION_REQUEST_DATA::ID => MISSION_REQUEST_DATA::EXTRA_CRC,
34010 SET_POSITION_TARGET_LOCAL_NED_DATA::ID => SET_POSITION_TARGET_LOCAL_NED_DATA::EXTRA_CRC,
34011 LOGGING_ACK_DATA::ID => LOGGING_ACK_DATA::EXTRA_CRC,
34012 CAN_FRAME_DATA::ID => CAN_FRAME_DATA::EXTRA_CRC,
34013 HIGH_LATENCY_DATA::ID => HIGH_LATENCY_DATA::EXTRA_CRC,
34014 VIBRATION_DATA::ID => VIBRATION_DATA::EXTRA_CRC,
34015 CHANGE_OPERATOR_CONTROL_DATA::ID => CHANGE_OPERATOR_CONTROL_DATA::EXTRA_CRC,
34016 MANUAL_SETPOINT_DATA::ID => MANUAL_SETPOINT_DATA::EXTRA_CRC,
34017 MOUNT_ORIENTATION_DATA::ID => MOUNT_ORIENTATION_DATA::EXTRA_CRC,
34018 MISSION_SET_CURRENT_DATA::ID => MISSION_SET_CURRENT_DATA::EXTRA_CRC,
34019 RAW_IMU_DATA::ID => RAW_IMU_DATA::EXTRA_CRC,
34020 RAW_PRESSURE_DATA::ID => RAW_PRESSURE_DATA::EXTRA_CRC,
34021 DATA_STREAM_DATA::ID => DATA_STREAM_DATA::EXTRA_CRC,
34022 OPEN_DRONE_ID_LOCATION_DATA::ID => OPEN_DRONE_ID_LOCATION_DATA::EXTRA_CRC,
34023 TUNNEL_DATA::ID => TUNNEL_DATA::EXTRA_CRC,
34024 NAMED_VALUE_FLOAT_DATA::ID => NAMED_VALUE_FLOAT_DATA::EXTRA_CRC,
34025 SIM_STATE_DATA::ID => SIM_STATE_DATA::EXTRA_CRC,
34026 OPEN_DRONE_ID_SYSTEM_DATA::ID => OPEN_DRONE_ID_SYSTEM_DATA::EXTRA_CRC,
34027 OPEN_DRONE_ID_OPERATOR_ID_DATA::ID => OPEN_DRONE_ID_OPERATOR_ID_DATA::EXTRA_CRC,
34028 MISSION_WRITE_PARTIAL_LIST_DATA::ID => MISSION_WRITE_PARTIAL_LIST_DATA::EXTRA_CRC,
34029 DEBUG_FLOAT_ARRAY_DATA::ID => DEBUG_FLOAT_ARRAY_DATA::EXTRA_CRC,
34030 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::ID => {
34031 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::EXTRA_CRC
34032 }
34033 PING_DATA::ID => PING_DATA::EXTRA_CRC,
34034 CAMERA_SETTINGS_DATA::ID => CAMERA_SETTINGS_DATA::EXTRA_CRC,
34035 TERRAIN_REQUEST_DATA::ID => TERRAIN_REQUEST_DATA::EXTRA_CRC,
34036 GIMBAL_DEVICE_SET_ATTITUDE_DATA::ID => GIMBAL_DEVICE_SET_ATTITUDE_DATA::EXTRA_CRC,
34037 ATT_POS_MOCAP_DATA::ID => ATT_POS_MOCAP_DATA::EXTRA_CRC,
34038 HEARTBEAT_DATA::ID => HEARTBEAT_DATA::EXTRA_CRC,
34039 OBSTACLE_DISTANCE_DATA::ID => OBSTACLE_DISTANCE_DATA::EXTRA_CRC,
34040 OPTICAL_FLOW_RAD_DATA::ID => OPTICAL_FLOW_RAD_DATA::EXTRA_CRC,
34041 HIL_GPS_DATA::ID => HIL_GPS_DATA::EXTRA_CRC,
34042 WINCH_STATUS_DATA::ID => WINCH_STATUS_DATA::EXTRA_CRC,
34043 GENERATOR_STATUS_DATA::ID => GENERATOR_STATUS_DATA::EXTRA_CRC,
34044 FILE_TRANSFER_PROTOCOL_DATA::ID => FILE_TRANSFER_PROTOCOL_DATA::EXTRA_CRC,
34045 DATA_TRANSMISSION_HANDSHAKE_DATA::ID => DATA_TRANSMISSION_HANDSHAKE_DATA::EXTRA_CRC,
34046 SUPPORTED_TUNES_DATA::ID => SUPPORTED_TUNES_DATA::EXTRA_CRC,
34047 SET_GPS_GLOBAL_ORIGIN_DATA::ID => SET_GPS_GLOBAL_ORIGIN_DATA::EXTRA_CRC,
34048 ATTITUDE_QUATERNION_DATA::ID => ATTITUDE_QUATERNION_DATA::EXTRA_CRC,
34049 TRAJECTORY_REPRESENTATION_BEZIER_DATA::ID => {
34050 TRAJECTORY_REPRESENTATION_BEZIER_DATA::EXTRA_CRC
34051 }
34052 FUEL_STATUS_DATA::ID => FUEL_STATUS_DATA::EXTRA_CRC,
34053 MISSION_CLEAR_ALL_DATA::ID => MISSION_CLEAR_ALL_DATA::EXTRA_CRC,
34054 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::ID => {
34055 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::EXTRA_CRC
34056 }
34057 LOGGING_DATA_ACKED_DATA::ID => LOGGING_DATA_ACKED_DATA::EXTRA_CRC,
34058 RESPONSE_EVENT_ERROR_DATA::ID => RESPONSE_EVENT_ERROR_DATA::EXTRA_CRC,
34059 SCALED_PRESSURE3_DATA::ID => SCALED_PRESSURE3_DATA::EXTRA_CRC,
34060 CANFD_FRAME_DATA::ID => CANFD_FRAME_DATA::EXTRA_CRC,
34061 MISSION_REQUEST_INT_DATA::ID => MISSION_REQUEST_INT_DATA::EXTRA_CRC,
34062 MAG_CAL_REPORT_DATA::ID => MAG_CAL_REPORT_DATA::EXTRA_CRC,
34063 COMMAND_ACK_DATA::ID => COMMAND_ACK_DATA::EXTRA_CRC,
34064 MISSION_ITEM_REACHED_DATA::ID => MISSION_ITEM_REACHED_DATA::EXTRA_CRC,
34065 CHANGE_OPERATOR_CONTROL_ACK_DATA::ID => CHANGE_OPERATOR_CONTROL_ACK_DATA::EXTRA_CRC,
34066 DEBUG_DATA::ID => DEBUG_DATA::EXTRA_CRC,
34067 MISSION_COUNT_DATA::ID => MISSION_COUNT_DATA::EXTRA_CRC,
34068 SERIAL_CONTROL_DATA::ID => SERIAL_CONTROL_DATA::EXTRA_CRC,
34069 GPS2_RAW_DATA::ID => GPS2_RAW_DATA::EXTRA_CRC,
34070 FLIGHT_INFORMATION_DATA::ID => FLIGHT_INFORMATION_DATA::EXTRA_CRC,
34071 GIMBAL_MANAGER_SET_ATTITUDE_DATA::ID => GIMBAL_MANAGER_SET_ATTITUDE_DATA::EXTRA_CRC,
34072 _ => 0,
34073 }
34074 }
34075 fn target_system_id(&self) -> Option<u8> {
34076 match self {
34077 Self::SET_HOME_POSITION(inner) => Some(inner.target_system),
34078 Self::OPEN_DRONE_ID_AUTHENTICATION(inner) => Some(inner.target_system),
34079 Self::MISSION_ACK(inner) => Some(inner.target_system),
34080 Self::SET_POSITION_TARGET_GLOBAL_INT(inner) => Some(inner.target_system),
34081 Self::PLAY_TUNE_V2(inner) => Some(inner.target_system),
34082 Self::OPEN_DRONE_ID_SELF_ID(inner) => Some(inner.target_system),
34083 Self::PARAM_SET(inner) => Some(inner.target_system),
34084 Self::SET_ACTUATOR_CONTROL_TARGET(inner) => Some(inner.target_system),
34085 Self::V2_EXTENSION(inner) => Some(inner.target_system),
34086 Self::LOG_REQUEST_DATA(inner) => Some(inner.target_system),
34087 Self::TIMESYNC(inner) => Some(inner.target_system),
34088 Self::LOGGING_DATA(inner) => Some(inner.target_system),
34089 Self::CAN_FILTER_MODIFY(inner) => Some(inner.target_system),
34090 Self::PARAM_EXT_SET(inner) => Some(inner.target_system),
34091 Self::SET_MODE(inner) => Some(inner.target_system),
34092 Self::PARAM_MAP_RC(inner) => Some(inner.target_system),
34093 Self::PARAM_EXT_REQUEST_READ(inner) => Some(inner.target_system),
34094 Self::PLAY_TUNE(inner) => Some(inner.target_system),
34095 Self::PARAM_REQUEST_LIST(inner) => Some(inner.target_system),
34096 Self::COMMAND_CANCEL(inner) => Some(inner.target_system),
34097 Self::COMMAND_INT(inner) => Some(inner.target_system),
34098 Self::GPS_INJECT_DATA(inner) => Some(inner.target_system),
34099 Self::REQUEST_EVENT(inner) => Some(inner.target_system),
34100 Self::REQUEST_DATA_STREAM(inner) => Some(inner.target_system),
34101 Self::RC_CHANNELS_OVERRIDE(inner) => Some(inner.target_system),
34102 Self::MISSION_REQUEST_LIST(inner) => Some(inner.target_system),
34103 Self::LOG_REQUEST_LIST(inner) => Some(inner.target_system),
34104 Self::SETUP_SIGNING(inner) => Some(inner.target_system),
34105 Self::SAFETY_SET_ALLOWED_AREA(inner) => Some(inner.target_system),
34106 Self::SET_ATTITUDE_TARGET(inner) => Some(inner.target_system),
34107 Self::OPEN_DRONE_ID_MESSAGE_PACK(inner) => Some(inner.target_system),
34108 Self::GIMBAL_MANAGER_SET_PITCHYAW(inner) => Some(inner.target_system),
34109 Self::COMMAND_LONG(inner) => Some(inner.target_system),
34110 Self::PARAM_EXT_REQUEST_LIST(inner) => Some(inner.target_system),
34111 Self::OPEN_DRONE_ID_BASIC_ID(inner) => Some(inner.target_system),
34112 Self::OPEN_DRONE_ID_SYSTEM_UPDATE(inner) => Some(inner.target_system),
34113 Self::MISSION_REQUEST_PARTIAL_LIST(inner) => Some(inner.target_system),
34114 Self::LOG_ERASE(inner) => Some(inner.target_system),
34115 Self::PARAM_REQUEST_READ(inner) => Some(inner.target_system),
34116 Self::MISSION_ITEM_INT(inner) => Some(inner.target_system),
34117 Self::MISSION_ITEM(inner) => Some(inner.target_system),
34118 Self::GIMBAL_DEVICE_ATTITUDE_STATUS(inner) => Some(inner.target_system),
34119 Self::LOG_REQUEST_END(inner) => Some(inner.target_system),
34120 Self::MISSION_REQUEST(inner) => Some(inner.target_system),
34121 Self::SET_POSITION_TARGET_LOCAL_NED(inner) => Some(inner.target_system),
34122 Self::LOGGING_ACK(inner) => Some(inner.target_system),
34123 Self::CAN_FRAME(inner) => Some(inner.target_system),
34124 Self::CHANGE_OPERATOR_CONTROL(inner) => Some(inner.target_system),
34125 Self::MISSION_SET_CURRENT(inner) => Some(inner.target_system),
34126 Self::OPEN_DRONE_ID_LOCATION(inner) => Some(inner.target_system),
34127 Self::TUNNEL(inner) => Some(inner.target_system),
34128 Self::OPEN_DRONE_ID_SYSTEM(inner) => Some(inner.target_system),
34129 Self::OPEN_DRONE_ID_OPERATOR_ID(inner) => Some(inner.target_system),
34130 Self::MISSION_WRITE_PARTIAL_LIST(inner) => Some(inner.target_system),
34131 Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL(inner) => Some(inner.target_system),
34132 Self::PING(inner) => Some(inner.target_system),
34133 Self::GIMBAL_DEVICE_SET_ATTITUDE(inner) => Some(inner.target_system),
34134 Self::FILE_TRANSFER_PROTOCOL(inner) => Some(inner.target_system),
34135 Self::SUPPORTED_TUNES(inner) => Some(inner.target_system),
34136 Self::SET_GPS_GLOBAL_ORIGIN(inner) => Some(inner.target_system),
34137 Self::MISSION_CLEAR_ALL(inner) => Some(inner.target_system),
34138 Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(inner) => Some(inner.target_system),
34139 Self::LOGGING_DATA_ACKED(inner) => Some(inner.target_system),
34140 Self::RESPONSE_EVENT_ERROR(inner) => Some(inner.target_system),
34141 Self::CANFD_FRAME(inner) => Some(inner.target_system),
34142 Self::MISSION_REQUEST_INT(inner) => Some(inner.target_system),
34143 Self::COMMAND_ACK(inner) => Some(inner.target_system),
34144 Self::MISSION_COUNT(inner) => Some(inner.target_system),
34145 Self::SERIAL_CONTROL(inner) => Some(inner.target_system),
34146 Self::GIMBAL_MANAGER_SET_ATTITUDE(inner) => Some(inner.target_system),
34147 _ => None,
34148 }
34149 }
34150 fn target_component_id(&self) -> Option<u8> {
34151 match self {
34152 Self::OPEN_DRONE_ID_AUTHENTICATION(inner) => Some(inner.target_component),
34153 Self::MISSION_ACK(inner) => Some(inner.target_component),
34154 Self::SET_POSITION_TARGET_GLOBAL_INT(inner) => Some(inner.target_component),
34155 Self::PLAY_TUNE_V2(inner) => Some(inner.target_component),
34156 Self::OPEN_DRONE_ID_SELF_ID(inner) => Some(inner.target_component),
34157 Self::PARAM_SET(inner) => Some(inner.target_component),
34158 Self::SET_ACTUATOR_CONTROL_TARGET(inner) => Some(inner.target_component),
34159 Self::V2_EXTENSION(inner) => Some(inner.target_component),
34160 Self::LOG_REQUEST_DATA(inner) => Some(inner.target_component),
34161 Self::TIMESYNC(inner) => Some(inner.target_component),
34162 Self::LOGGING_DATA(inner) => Some(inner.target_component),
34163 Self::CAN_FILTER_MODIFY(inner) => Some(inner.target_component),
34164 Self::PARAM_EXT_SET(inner) => Some(inner.target_component),
34165 Self::PARAM_MAP_RC(inner) => Some(inner.target_component),
34166 Self::PARAM_EXT_REQUEST_READ(inner) => Some(inner.target_component),
34167 Self::PLAY_TUNE(inner) => Some(inner.target_component),
34168 Self::PARAM_REQUEST_LIST(inner) => Some(inner.target_component),
34169 Self::COMMAND_CANCEL(inner) => Some(inner.target_component),
34170 Self::COMMAND_INT(inner) => Some(inner.target_component),
34171 Self::GPS_INJECT_DATA(inner) => Some(inner.target_component),
34172 Self::REQUEST_EVENT(inner) => Some(inner.target_component),
34173 Self::REQUEST_DATA_STREAM(inner) => Some(inner.target_component),
34174 Self::RC_CHANNELS_OVERRIDE(inner) => Some(inner.target_component),
34175 Self::MISSION_REQUEST_LIST(inner) => Some(inner.target_component),
34176 Self::LOG_REQUEST_LIST(inner) => Some(inner.target_component),
34177 Self::SETUP_SIGNING(inner) => Some(inner.target_component),
34178 Self::SAFETY_SET_ALLOWED_AREA(inner) => Some(inner.target_component),
34179 Self::SET_ATTITUDE_TARGET(inner) => Some(inner.target_component),
34180 Self::OPEN_DRONE_ID_MESSAGE_PACK(inner) => Some(inner.target_component),
34181 Self::GIMBAL_MANAGER_SET_PITCHYAW(inner) => Some(inner.target_component),
34182 Self::COMMAND_LONG(inner) => Some(inner.target_component),
34183 Self::PARAM_EXT_REQUEST_LIST(inner) => Some(inner.target_component),
34184 Self::OPEN_DRONE_ID_BASIC_ID(inner) => Some(inner.target_component),
34185 Self::OPEN_DRONE_ID_SYSTEM_UPDATE(inner) => Some(inner.target_component),
34186 Self::MISSION_REQUEST_PARTIAL_LIST(inner) => Some(inner.target_component),
34187 Self::LOG_ERASE(inner) => Some(inner.target_component),
34188 Self::PARAM_REQUEST_READ(inner) => Some(inner.target_component),
34189 Self::MISSION_ITEM_INT(inner) => Some(inner.target_component),
34190 Self::MISSION_ITEM(inner) => Some(inner.target_component),
34191 Self::GIMBAL_DEVICE_ATTITUDE_STATUS(inner) => Some(inner.target_component),
34192 Self::LOG_REQUEST_END(inner) => Some(inner.target_component),
34193 Self::MISSION_REQUEST(inner) => Some(inner.target_component),
34194 Self::SET_POSITION_TARGET_LOCAL_NED(inner) => Some(inner.target_component),
34195 Self::LOGGING_ACK(inner) => Some(inner.target_component),
34196 Self::CAN_FRAME(inner) => Some(inner.target_component),
34197 Self::MISSION_SET_CURRENT(inner) => Some(inner.target_component),
34198 Self::OPEN_DRONE_ID_LOCATION(inner) => Some(inner.target_component),
34199 Self::TUNNEL(inner) => Some(inner.target_component),
34200 Self::OPEN_DRONE_ID_SYSTEM(inner) => Some(inner.target_component),
34201 Self::OPEN_DRONE_ID_OPERATOR_ID(inner) => Some(inner.target_component),
34202 Self::MISSION_WRITE_PARTIAL_LIST(inner) => Some(inner.target_component),
34203 Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL(inner) => Some(inner.target_component),
34204 Self::PING(inner) => Some(inner.target_component),
34205 Self::GIMBAL_DEVICE_SET_ATTITUDE(inner) => Some(inner.target_component),
34206 Self::FILE_TRANSFER_PROTOCOL(inner) => Some(inner.target_component),
34207 Self::SUPPORTED_TUNES(inner) => Some(inner.target_component),
34208 Self::MISSION_CLEAR_ALL(inner) => Some(inner.target_component),
34209 Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(inner) => Some(inner.target_component),
34210 Self::LOGGING_DATA_ACKED(inner) => Some(inner.target_component),
34211 Self::RESPONSE_EVENT_ERROR(inner) => Some(inner.target_component),
34212 Self::CANFD_FRAME(inner) => Some(inner.target_component),
34213 Self::MISSION_REQUEST_INT(inner) => Some(inner.target_component),
34214 Self::COMMAND_ACK(inner) => Some(inner.target_component),
34215 Self::MISSION_COUNT(inner) => Some(inner.target_component),
34216 Self::SERIAL_CONTROL(inner) => Some(inner.target_component),
34217 Self::GIMBAL_MANAGER_SET_ATTITUDE(inner) => Some(inner.target_component),
34218 _ => None,
34219 }
34220 }
34221}